From 92c19f2d7479a4fd15f4603c7924762485a3e6ce Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Sun, 24 Nov 2013 17:29:38 -0500 Subject: [PATCH 001/203] Changed the element id's in one of the SVG files that I incorrectly edited. This prevents the error: Could not resolve property : SVGID_1_ Error comes from qsvghandler.cpp or qsvgstyle.cpp in the QT libraries Qt5.2.0//5.2.0-beta1/Src/qtsvg/src/svg/ The fixedwing-shapes.svg and flyingwing-shapes.svg files need modified to prevent the errors caused by qsvgtinydocument.cpp in the QT libraries. Couldn't find node aileron. Skipping rendering. Couldn't find node vtail. Skipping rendering. These errors come from the case statement that was added to updateImageAnd Description() for FixedWingPage + switch (type) { + case SetupWizard::FIXED_WING_AILERON: + elementId = "aileron"; + break; + case SetupWizard::FIXED_WING_VTAIL: + elementId = "vtail"; + break; + default: + elementId = ""; + break; + } A similar error needs to be resolved in connectiondiagram.cpp + switch (m_configSource->getVehicleSubType()) { + case VehicleConfigurationSource::FIXED_WING_AILERON: + elementsToShow << "aileron"; + break; + case VehicleConfigurationSource::FIXED_WING_VTAIL: + elementsToShow << "vtail"; + break; + default: + break; + } Likewise outputcalibrationpage.cpp will need to reverence the elements inside the SVG file properly. + m_vehicleElementIds << "fixed-aileron" << "aileron"; + m_vehicleHighlightElementIndexes << 0 << 1; ... + m_vehicleElementIds << "fixed-vtail" << "vtail"; + m_vehicleHighlightElementIndexes << 0 << 1; Until these elements are fixed in the SVG files the wizard will not render properly and allow the user to click *next*. --- .../src/plugins/config/configgadget.qrc | 3 + .../config/images/fixedwing-shapes.svg | 4 +- .../plugins/setupwizard/connectiondiagram.cpp | 10 ++ .../setupwizard/pages/fixedwingpage.cpp | 83 ++++++++- .../plugins/setupwizard/pages/fixedwingpage.h | 17 ++ .../setupwizard/pages/fixedwingpage.ui | 155 +++++++++++++++-- .../pages/outputcalibrationpage.cpp | 17 ++ .../plugins/setupwizard/pages/vehiclepage.ui | 2 +- .../src/plugins/setupwizard/setupwizard.cpp | 17 +- .../vehicleconfigurationhelper.cpp | 157 ++++++++++++++++++ .../setupwizard/vehicleconfigurationhelper.h | 3 + .../plugins/setupwizard/wizardResources.qrc | 3 + 12 files changed, 451 insertions(+), 20 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configgadget.qrc b/ground/openpilotgcs/src/plugins/config/configgadget.qrc index adffc9568..c2e2ab810 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadget.qrc +++ b/ground/openpilotgcs/src/plugins/config/configgadget.qrc @@ -4,6 +4,9 @@ images/ahrs-calib.svg images/paper-plane.svg images/multirotor-shapes.svg + + images/fixedwing-shapes.svg + images/flyingwing-shapes.svg images/ccpm_setup.svg images/PipXtreme.png images/help.png diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index 63421dc38..cc85dab08 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -1,7 +1,7 @@ - - + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp index 4a19eb4cf..e69bf039b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -118,6 +118,16 @@ void ConnectionDiagram::setupGraphicsScene() } break; case VehicleConfigurationSource::VEHICLE_FIXEDWING: + switch (m_configSource->getVehicleSubType()) { + case VehicleConfigurationSource::FIXED_WING_AILERON: + elementsToShow << "aileron"; + break; + case VehicleConfigurationSource::FIXED_WING_VTAIL: + elementsToShow << "vtail"; + break; + default: + break; + } case VehicleConfigurationSource::VEHICLE_HELI: case VehicleConfigurationSource::VEHICLE_SURFACE: default: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index 7295cc8a3..4c1db8e67 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -27,16 +27,97 @@ #include "fixedwingpage.h" #include "ui_fixedwingpage.h" +#include "setupwizard.h" FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) : AbstractWizardPage(wizard, parent), ui(new Ui::FixedWingPage) { ui->setupUi(this); - setFinalPage(true); + QSvgRenderer *renderer = new QSvgRenderer(); +// What do we do about v-tail here? + renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); + m_fixedwingPic = new QGraphicsSvgItem(); + m_fixedwingPic->setSharedRenderer(renderer); + QGraphicsScene *scene = new QGraphicsScene(this); + scene->addItem(m_fixedwingPic); + ui->typeGraphicsView->setScene(scene); + + setupFixedWingTypesCombo(); + + // Default to Aileron setup + ui->typeCombo->setCurrentIndex(0); + connect(ui->typeCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateImageAndDescription())); + ui->typeGraphicsView->setSceneRect(m_fixedwingPic->boundingRect()); + ui->typeGraphicsView->fitInView(m_fixedwingPic, Qt::KeepAspectRatio); + } FixedWingPage::~FixedWingPage() { delete ui; } + +void FixedWingPage::initializePage() +{ + updateAvailableTypes(); + updateImageAndDescription(); +} + +bool FixedWingPage::validatePage() +{ + SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE)ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); + + getWizard()->setVehicleSubType(type); + return true; +} + +void FixedWingPage::resizeEvent(QResizeEvent *event) +{ + Q_UNUSED(event); + if (m_fixedwingPic) { + ui->typeGraphicsView->setSceneRect(m_fixedwingPic->boundingRect()); + ui->typeGraphicsView->fitInView(m_fixedwingPic, Qt::KeepAspectRatio); + } +} + +void FixedWingPage::setupFixedWingTypesCombo() +{ + ui->typeCombo->addItem(tr("Aileron, Elevator, Rudder"), SetupWizard::FIXED_WING_AILERON); + m_descriptions << tr("A description for aileron driven fixed wing stuff goes here... "); + + ui->typeCombo->addItem(tr("V-Tail, or Elevon"), SetupWizard::FIXED_WING_VTAIL); + m_descriptions << tr("A description for vtail driven fixed wing stuff goes here... "); +} + +void FixedWingPage::updateAvailableTypes() +{ +} + +void FixedWingPage::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::FIXED_WING_AILERON: + elementId = "aileron"; + break; + case SetupWizard::FIXED_WING_VTAIL: + elementId = "vtail"; + break; + default: + elementId = ""; + break; + } + m_fixedwingPic->setElementId(elementId); + ui->typeGraphicsView->setSceneRect(m_fixedwingPic->boundingRect()); + ui->typeGraphicsView->fitInView(m_fixedwingPic, Qt::KeepAspectRatio); + + ui->typeDescription->setText(description); + +} + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h index 6a99ef2fe..593be37bb 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h @@ -28,6 +28,10 @@ #ifndef FIXEDWINGPAGE_H #define FIXEDWINGPAGE_H +#include +#include +#include + #include "abstractwizardpage.h" namespace Ui { @@ -41,8 +45,21 @@ public: explicit FixedWingPage(SetupWizard *wizard, QWidget *parent = 0); ~FixedWingPage(); + void initializePage(); + bool validatePage(); + +protected: + void resizeEvent(QResizeEvent *event); + private: Ui::FixedWingPage *ui; + void setupFixedWingTypesCombo(); + QGraphicsSvgItem *m_fixedwingPic; + void updateAvailableTypes(); + QList m_descriptions; + +private slots: + void updateImageAndDescription(); }; #endif // FIXEDWINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui index 8b478be7d..ad47e2685 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui @@ -15,22 +15,147 @@ - - - <!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> + + + <!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 fixedwing 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 fixedwings. Other variants of fixedwings 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 fixedwing you want to create a configuration for below:</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + 4 - - Qt::AlignCenter - - - true - - + + + + + + 4 + + + + + + 125 + 36 + + + + + 10 + 50 + false + + + + Multirotor type: + + + + + + + + 125 + 20 + + + + + + + + + + + 0 + 0 + + + + Qt::ScrollBarAlwaysOn + + + Qt::ScrollBarAlwaysOff + + + Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse + + + + + + + + + + 0 + 0 + + + + + 200 + 200 + + + + true + + + QFrame::NoFrame + + + 0 + + + 0 + + + Qt::ScrollBarAlwaysOff + + + Qt::ScrollBarAlwaysOff + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + false + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index c1eebfa1d..f43304352 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -104,6 +104,23 @@ void OutputCalibrationPage::setupVehicle() m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6; m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; break; +// KF hack + case SetupWizard::FIXED_WING_AILERON: + qDebug() << "no clue what a wizard index is!"; + m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; + m_vehicleElementIds << "fixed-aileron" << "aileron"; + m_vehicleHighlightElementIndexes << 0 << 1; + m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; + getWizard()->setActuatorSettings(m_actuatorSettings); + break; + case SetupWizard::FIXED_WING_VTAIL: + qDebug() << "no clue what a wizard index is!"; + m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; + m_vehicleElementIds << "fixed-vtail" << "vtail"; + m_vehicleHighlightElementIndexes << 0 << 1; + m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; + getWizard()->setActuatorSettings(m_actuatorSettings); + break; default: break; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui index a6e0e9354..34d9531fe 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui @@ -146,7 +146,7 @@ p, li { white-space: pre-wrap; } - false + true diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index de3b20063..03073cc6d 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -225,7 +225,22 @@ QString SetupWizard::getSummaryText() break; case VEHICLE_FIXEDWING: - summary.append(tr("Fixed wing")); + summary.append(tr("Fixed wing")); + + summary.append("
"); + summary.append("").append(tr("Vehicle sub type: ")).append(""); + switch (getVehicleSubType()) { + case SetupWizard::FIXED_WING_AILERON: + summary.append(tr("Aileron")); + break; + case SetupWizard::FIXED_WING_VTAIL: + summary.append(tr("Vtail")); + break; + default: + summary.append(tr("Unknown")); + break; + } + break; case VEHICLE_HELI: summary.append(tr("Helicopter")); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 6d8e0fd7d..e07a614d9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -214,6 +214,22 @@ void VehicleConfigurationHelper::applyVehicleConfiguration() break; } case VehicleConfigurationSource::VEHICLE_FIXEDWING: + { + switch (m_configSource->getVehicleSubType()) { + case VehicleConfigurationSource::FIXED_WING_AILERON: + setupAileron(); + break; +/* case VehicleConfigurationSource::FIXED_WING_ELEVON: + setupElevon(); + break; */ + case VehicleConfigurationSource::FIXED_WING_VTAIL: + setupVtail(); + break; + default: + break; + } + break; + } case VehicleConfigurationSource::VEHICLE_HELI: case VehicleConfigurationSource::VEHICLE_SURFACE: // TODO: Implement settings for other vehicle types? @@ -1287,3 +1303,144 @@ void VehicleConfigurationHelper::setupOctoCopter() applyMixerConfiguration(channels); applyMultiGUISettings(frame, guiSettings); } + +// This is all wrong... I just copied the Tricopter stuff +void VehicleConfigurationHelper::setupVtail() +{ + + mixerChannelSettings channels[10]; + GUIConfigDataUnion guiSettings = getGUIConfigData(); + + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = 100; + channels[0].pitch = 50; + channels[0].yaw = 0; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = -100; + channels[1].pitch = 50; + channels[1].yaw = 0; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = 0; + channels[2].pitch = -100; + channels[2].yaw = 0; + + channels[3].type = MIXER_TYPE_SERVO; + channels[3].throttle1 = 0; + channels[3].throttle2 = 0; + channels[3].roll = 0; + channels[3].pitch = 0; + channels[3].yaw = 100; + + guiSettings.multi.VTOLMotorNW = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorS = 3; + guiSettings.multi.TRIYaw = 4; + + applyMixerConfiguration(channels); + applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL, guiSettings); +} + +// This is all wrong... I just copied the Tricopter stuff +void VehicleConfigurationHelper::setupAileron() +{ + // Typical vehicle setup + // 1. Setup mixer data + // 2. Setup GUI data + // 3. Apply changes + + mixerChannelSettings channels[10]; + GUIConfigDataUnion guiSettings = getGUIConfigData(); + + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = 100; + channels[0].pitch = 50; + channels[0].yaw = 0; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = -100; + channels[1].pitch = 50; + channels[1].yaw = 0; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = 0; + channels[2].pitch = -100; + channels[2].yaw = 0; + + channels[3].type = MIXER_TYPE_SERVO; + channels[3].throttle1 = 0; + channels[3].throttle2 = 0; + channels[3].roll = 0; + channels[3].pitch = 0; + channels[3].yaw = 100; + + guiSettings.multi.VTOLMotorNW = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorS = 3; + guiSettings.multi.TRIYaw = 4; + + applyMixerConfiguration(channels); + applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL, guiSettings); +} + +// This is all wrong... I just copied the Tricopter stuff +void VehicleConfigurationHelper::setupElevon() +{ + // Typical vehicle setup + // 1. Setup mixer data + // 2. Setup GUI data + // 3. Apply changes + + mixerChannelSettings channels[10]; + GUIConfigDataUnion guiSettings = getGUIConfigData(); + + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = 100; + channels[0].pitch = 50; + channels[0].yaw = 0; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = -100; + channels[1].pitch = 50; + channels[1].yaw = 0; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = 0; + channels[2].pitch = -100; + channels[2].yaw = 0; + + channels[3].type = MIXER_TYPE_SERVO; + channels[3].throttle1 = 0; + channels[3].throttle2 = 0; + channels[3].roll = 0; + channels[3].pitch = 0; + channels[3].yaw = 100; + + guiSettings.multi.VTOLMotorNW = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorS = 3; + guiSettings.multi.TRIYaw = 4; + + applyMixerConfiguration(channels); + applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON, guiSettings); +} + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h index 1ed1aa576..197f1a435 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h @@ -103,6 +103,9 @@ private: void setupQuadCopter(); void setupHexaCopter(); void setupOctoCopter(); + void setupVtail(); + void setupAileron(); + void setupElevon(); private slots: void uAVOTransactionCompleted(UAVObject *object, bool success); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index 1ee031d0e..2c1c13e3c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -30,6 +30,9 @@ resources/bttn-turbo-down.png resources/bttn-turbo-up.png resources/multirotor-shapes.svg + + resources/fixedwing-shapes.svg + resources/flyingwing-shapes.svg resources/bttn-illustration-down.png resources/bttn-illustration-up.png resources/bttn-save-down.png From 0d5e91ee266bf3f75ebae4b501fe1ce5d488c8b4 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Mon, 25 Nov 2013 01:06:07 -0500 Subject: [PATCH 002/203] I fixed the first screen, now the vtail and aileron models show when slected. For some reason I am unable to move beyond the first wizard screen. --- .../src/plugins/config/configgadget.qrc | 1 - .../config/images/fixedwing-shapes.svg | 3625 +++++++++++++---- .../config/images/flyingwing-shapes.svg | 544 --- .../setupwizard/pages/fixedwingpage.cpp | 1 - .../setupwizard/pages/fixedwingpage.ui | 2 +- .../pages/outputcalibrationpage.cpp | 7 +- .../resources/fixedwing-shapes.svg | 3625 +++++++++++++---- .../resources/flyingwing-shapes.svg | 544 --- .../plugins/setupwizard/wizardResources.qrc | 1 - 9 files changed, 5584 insertions(+), 2766 deletions(-) delete mode 100644 ground/openpilotgcs/src/plugins/config/images/flyingwing-shapes.svg delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/flyingwing-shapes.svg diff --git a/ground/openpilotgcs/src/plugins/config/configgadget.qrc b/ground/openpilotgcs/src/plugins/config/configgadget.qrc index c2e2ab810..f58ce7203 100644 --- a/ground/openpilotgcs/src/plugins/config/configgadget.qrc +++ b/ground/openpilotgcs/src/plugins/config/configgadget.qrc @@ -6,7 +6,6 @@ images/multirotor-shapes.svg images/fixedwing-shapes.svg - images/flyingwing-shapes.svg images/ccpm_setup.svg images/PipXtreme.png images/help.png diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index cc85dab08..e99a33c65 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -1,836 +1,2789 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + +image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/config/images/flyingwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/flyingwing-shapes.svg deleted file mode 100644 index 62ecd3aaf..000000000 --- a/ground/openpilotgcs/src/plugins/config/images/flyingwing-shapes.svg +++ /dev/null @@ -1,544 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index 4c1db8e67..543da261e 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -35,7 +35,6 @@ FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) : { ui->setupUi(this); QSvgRenderer *renderer = new QSvgRenderer(); -// What do we do about v-tail here? renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); m_fixedwingPic = new QGraphicsSvgItem(); m_fixedwingPic->setSharedRenderer(renderer); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui index ad47e2685..b1c5f253f 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui @@ -63,7 +63,7 @@ - Multirotor type: + FixedWing type: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index f43304352..a6e5d74f9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -36,6 +36,7 @@ OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *paren { ui->setupUi(this); + qDebug() << "calling output calibration page"; m_vehicleRenderer = new QSvgRenderer(); if (QFile::exists(QString(":/setupwizard/resources/multirotor-shapes.svg")) && m_vehicleRenderer->load(QString(":/setupwizard/resources/multirotor-shapes.svg")) && @@ -107,7 +108,8 @@ void OutputCalibrationPage::setupVehicle() // KF hack case SetupWizard::FIXED_WING_AILERON: qDebug() << "no clue what a wizard index is!"; - m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; +// m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; + m_wizardIndexes << 0 << 1 << 1 << 1 << 2 << 3 << 4; m_vehicleElementIds << "fixed-aileron" << "aileron"; m_vehicleHighlightElementIndexes << 0 << 1; m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; @@ -115,7 +117,8 @@ void OutputCalibrationPage::setupVehicle() break; case SetupWizard::FIXED_WING_VTAIL: qDebug() << "no clue what a wizard index is!"; - m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; +// m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; + m_wizardIndexes << 0 << 1 << 1 << 1 << 2 << 3 << 4; m_vehicleElementIds << "fixed-vtail" << "vtail"; m_vehicleHighlightElementIndexes << 0 << 1; m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg index 63421dc38..e99a33c65 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg @@ -1,836 +1,2789 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + +image/svg+xml + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/flyingwing-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/flyingwing-shapes.svg deleted file mode 100644 index 62ecd3aaf..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/flyingwing-shapes.svg +++ /dev/null @@ -1,544 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index 2c1c13e3c..507b4c877 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -32,7 +32,6 @@ resources/multirotor-shapes.svg resources/fixedwing-shapes.svg - resources/flyingwing-shapes.svg resources/bttn-illustration-down.png resources/bttn-illustration-up.png resources/bttn-save-down.png From 2b585a861878ef034c236966d6605f55b08836cf Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Sat, 14 Dec 2013 16:46:26 -0500 Subject: [PATCH 003/203] added a case statement for PAGE_FIXEDWING to trigger PAGE_OUTPUT --- ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 03073cc6d..449296f5b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -112,6 +112,9 @@ int SetupWizard::nextId() const case PAGE_MULTI: return PAGE_OUTPUT; + case PAGE_FIXEDWING: + return PAGE_OUTPUT; + case PAGE_INPUT: if (isRestartNeeded()) { saveHardwareSettings(); From a042ffd843338d69270b698482132b16b6f80784 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Sun, 15 Dec 2013 03:38:12 -0500 Subject: [PATCH 004/203] just trying to cleanup a bad push from last night. I stomped on some things I should not have. --- .../openpilotgcs/src/plugins/config/airframe_fixedwing.ui | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui index 1b42f042d..176b5daca 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui @@ -37,6 +37,14 @@ Airplane type: + + + + 0 + 0 + + + From 632ffed7079e9528aaa435069ac5cb504b996449 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Sun, 15 Dec 2013 21:37:19 -0500 Subject: [PATCH 005/203] Add the fixed wing plane art to the channel config screen (in progress) Begin adding plane art to Output config screen in wizard. --- .../configfixedwingwidget.cpp | 99 +++++++++++++++++-- .../cfg_vehicletypes/configfixedwingwidget.h | 15 ++- .../pages/outputcalibrationpage.cpp | 3 + 3 files changed, 104 insertions(+), 13 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 1a667fa5e..57a204a10 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -40,6 +40,8 @@ #include #include +const QString ConfigFixedWingWidget::CHANNELBOXNAME = QString("fixedWingChannelBox"); + QStringList ConfigFixedWingWidget::getChannelDescriptions() { // init a channel_numelem list of channel desc defaults @@ -83,6 +85,32 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : populateChannelComboBoxes(); + QSvgRenderer *renderer = new QSvgRenderer(); + renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); + plane = new QGraphicsSvgItem(); + plane->setSharedRenderer(renderer); + + QString type = "aileron"; // This needs fixed. Need to be able to obtain the aircraft type. + + // not sure why m_aircraft->fixedWingType->currentText() is not working here! fix it + if (type == "vtail") + { + plane->setElementId("vtail"); + } + else if (type == "aileron") + { + plane->setElementId("aileron"); + } + else + { + plane->setElementId("unknown"); + } + + QGraphicsScene *scene = new QGraphicsScene(); + scene->addItem(plane); + scene->setSceneRect(plane->boundingRect()); + m_aircraft->planeShape->setScene(scene); + QStringList fixedWingTypes; fixedWingTypes << "Elevator aileron rudder" << "Elevon" << "Vtail"; m_aircraft->fixedWingType->addItems(fixedWingTypes); @@ -90,6 +118,7 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : // Set default model to "Elevator aileron rudder" connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); + setupUI(m_aircraft->fixedWingType->currentText()); } @@ -158,6 +187,26 @@ void ConfigFixedWingWidget::setupUI(QString frameType) } } +void ConfigFixedWingWidget::setupEnabledControls(QString frameType) +{ + + // disable all motor channel boxes + for (int i = 1; i <= 8; i++) { + // do it manually so we can turn off any error decorations + QComboBox *combobox = this->findChild("fixedWingChannelBox" + QString::number(i)); + if (combobox) { + combobox->setEnabled(false); + combobox->setItemData(0, 0, Qt::DecorationRole); + } + } + + if (frameType == "Vtail" || frameType == "Elevon") { + enableComboBoxes(this, CHANNELBOXNAME, 3, true); + } else if (frameType == "aileron" || frameType == "Elevator aileron rudder") { + enableComboBoxes(this, CHANNELBOXNAME, 4, true); + } +} + void ConfigFixedWingWidget::registerWidgets(ConfigTaskWidget &parent) { parent.addWidget(m_aircraft->fixedWingThrottle->getCurveWidget()); @@ -278,6 +327,16 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() return airframeType; } +void ConfigFixedWingWidget::updateAirframe(QString frameType) +{ + qDebug() << "ConfigFixedWingWidget::updateAirframe - frame type" << frameType; + + // this is not doing anything right now + + m_aircraft->planeShape->setSceneRect(plane->boundingRect()); + m_aircraft->planeShape->fitInView(plane, Qt::KeepAspectRatio); +} + /** Setup Elevator/Aileron/Rudder airframe. @@ -502,15 +561,6 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType) return true; } -void ConfigFixedWingWidget::enableControls(bool enable) -{ - ConfigTaskWidget::enableControls(enable); - - if (enable) { - setupUI(m_aircraft->fixedWingType->currentText()); - } -} - /** This function displays text and color formatting in order to help the user understand what channels have not yet been configured. */ @@ -600,3 +650,34 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) return error; } + +/** + WHAT DOES THIS DO??? + */ +void ConfigFixedWingWidget::showEvent(QShowEvent *event) +{ + Q_UNUSED(event) + // Thit fitInView method should only be called now, once the + // widget is shown, otherwise it cannot compute its values and + // the result is usually a ahrsbargraph that is way too small. + m_aircraft->planeShape->fitInView(plane, Qt::KeepAspectRatio); +} + +/** + Resize the GUI contents when the user changes the window size + */ +void ConfigFixedWingWidget::resizeEvent(QResizeEvent *event) +{ + Q_UNUSED(event); + m_aircraft->planeShape->fitInView(plane, Qt::KeepAspectRatio); +} + +void ConfigFixedWingWidget::enableControls(bool enable) +{ + ConfigTaskWidget::enableControls(enable); + + if (enable) { + setupEnabledControls(m_aircraft->fixedWingType->currentText()); + } +} + diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index 65c03c86e..da8ef3839 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -34,8 +34,9 @@ #include "uavobjectmanager.h" #include "uavobject.h" #include "uavtalk/telemetrymanager.h" + +#include #include -#include #include class Ui_Widget; @@ -44,6 +45,7 @@ class ConfigFixedWingWidget : public VehicleConfig { Q_OBJECT public: + static const QString CHANNELBOXNAME; static QStringList getChannelDescriptions(); ConfigFixedWingWidget(QWidget *parent = 0); @@ -52,8 +54,14 @@ public: virtual void refreshWidgetsValues(QString frameType); virtual QString updateConfigObjectsFromWidgets(); +protected: + void showEvent(QShowEvent *event); + void resizeEvent(QResizeEvent *event); + void enableControls(bool enable); + private: Ui_FixedWingConfigWidget *m_aircraft; + QGraphicsSvgItem *plane; virtual void registerWidgets(ConfigTaskWidget &parent); virtual void resetActuators(GUIConfigDataUnion *configData); @@ -62,9 +70,8 @@ private: bool setupFrameElevon(QString airframeType); bool setupFrameVtail(QString airframeType); -protected: - void enableControls(bool enable); - + void updateAirframe(QString multiRotorType); + void setupEnabledControls(QString airframeType); private slots: virtual void setupUI(QString airframeType); virtual bool throwConfigError(QString airframeType); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index a6e5d74f9..2741e1b7b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -38,6 +38,9 @@ OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *paren qDebug() << "calling output calibration page"; m_vehicleRenderer = new QSvgRenderer(); + +// need to determine multi rotor or fixed wing. and pick the right svg + if (QFile::exists(QString(":/setupwizard/resources/multirotor-shapes.svg")) && m_vehicleRenderer->load(QString(":/setupwizard/resources/multirotor-shapes.svg")) && m_vehicleRenderer->isValid()) { From 82e2c5cf924613c654a97579bfd3f483d956df37 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Mon, 16 Dec 2013 14:29:04 -0500 Subject: [PATCH 006/203] Move some code around to accomidate multiple svg images in the output calibration screen. Need to fix the SVG to allow for zooming in on specific channel components as we do with the multi rotor screen. This has some sloppy comments in if for my own debugging purposes. --- .../configfixedwingwidget.cpp | 1 + .../pages/outputcalibrationpage.cpp | 55 ++++++++++++++++--- 2 files changed, 49 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 57a204a10..af76c818d 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -92,6 +92,7 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : QString type = "aileron"; // This needs fixed. Need to be able to obtain the aircraft type. + qDebug() << "Current Aircraft type: " << m_aircraft->fixedWingType->currentText(); // not sure why m_aircraft->fixedWingType->currentText() is not working here! fix it if (type == "vtail") { diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 2741e1b7b..1bbd4b4cc 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -39,14 +39,10 @@ OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *paren qDebug() << "calling output calibration page"; m_vehicleRenderer = new QSvgRenderer(); -// need to determine multi rotor or fixed wing. and pick the right svg + // move the code that was here to setupVehicle() so we can determine which image to use. + m_vehicleScene = new QGraphicsScene(this); + ui->vehicleView->setScene(m_vehicleScene); - 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() @@ -67,8 +63,18 @@ void OutputCalibrationPage::setupVehicle() m_channelIndex.clear(); m_currentWizardIndex = 0; m_vehicleScene->clear(); + +// KF moved code from OutputCalibrationPage() here so it can be used to detect the current vehicle +// needs to be slimmed down and not repeated. + switch (getWizard()->getVehicleSubType()) { case SetupWizard::MULTI_ROTOR_TRI_Y: + if (QFile::exists(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->load(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->isValid()) { + ui->vehicleView->setScene(m_vehicleScene); + } + 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; @@ -79,30 +85,55 @@ void OutputCalibrationPage::setupVehicle() getWizard()->setActuatorSettings(m_actuatorSettings); break; case SetupWizard::MULTI_ROTOR_QUAD_X: + if (QFile::exists(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->load(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->isValid()) { + ui->vehicleView->setScene(m_vehicleScene); + } 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: + if (QFile::exists(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->load(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->isValid()) { + ui->vehicleView->setScene(m_vehicleScene); + } 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: + if (QFile::exists(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->load(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->isValid()) { + ui->vehicleView->setScene(m_vehicleScene); + } 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: + if (QFile::exists(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->load(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->isValid()) { + ui->vehicleView->setScene(m_vehicleScene); + } 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: + if (QFile::exists(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->load(QString(":/setupwizard/resources/multirotor-shapes.svg")) && + m_vehicleRenderer->isValid()) { + ui->vehicleView->setScene(m_vehicleScene); + } 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; @@ -110,6 +141,11 @@ void OutputCalibrationPage::setupVehicle() break; // KF hack case SetupWizard::FIXED_WING_AILERON: + if (QFile::exists(QString(":/setupwizard/resources/fixedwing-shapes.svg")) && + m_vehicleRenderer->load(QString(":/setupwizard/resources/fixedwing-shapes.svg")) && + m_vehicleRenderer->isValid()) { + ui->vehicleView->setScene(m_vehicleScene); + } qDebug() << "no clue what a wizard index is!"; // m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; m_wizardIndexes << 0 << 1 << 1 << 1 << 2 << 3 << 4; @@ -119,6 +155,11 @@ void OutputCalibrationPage::setupVehicle() getWizard()->setActuatorSettings(m_actuatorSettings); break; case SetupWizard::FIXED_WING_VTAIL: + if (QFile::exists(QString(":/setupwizard/resources/fixedwing-shapes.svg")) && + m_vehicleRenderer->load(QString(":/setupwizard/resources/fixedwing-shapes.svg")) && + m_vehicleRenderer->isValid()) { + ui->vehicleView->setScene(m_vehicleScene); + } qDebug() << "no clue what a wizard index is!"; // m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; m_wizardIndexes << 0 << 1 << 1 << 1 << 2 << 3 << 4; From a960fd5c852dc84eafeebe5d8cc8bd1036263c06 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Mon, 16 Dec 2013 15:18:43 -0500 Subject: [PATCH 007/203] Fix the Configuration screen to show the new fixed wing artwork by Zen_ --- .../configfixedwingwidget.cpp | 45 ++++++++----------- 1 file changed, 18 insertions(+), 27 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index af76c818d..1c26cc512 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -85,33 +85,6 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : populateChannelComboBoxes(); - QSvgRenderer *renderer = new QSvgRenderer(); - renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); - plane = new QGraphicsSvgItem(); - plane->setSharedRenderer(renderer); - - QString type = "aileron"; // This needs fixed. Need to be able to obtain the aircraft type. - - qDebug() << "Current Aircraft type: " << m_aircraft->fixedWingType->currentText(); - // not sure why m_aircraft->fixedWingType->currentText() is not working here! fix it - if (type == "vtail") - { - plane->setElementId("vtail"); - } - else if (type == "aileron") - { - plane->setElementId("aileron"); - } - else - { - plane->setElementId("unknown"); - } - - QGraphicsScene *scene = new QGraphicsScene(); - scene->addItem(plane); - scene->setSceneRect(plane->boundingRect()); - m_aircraft->planeShape->setScene(scene); - QStringList fixedWingTypes; fixedWingTypes << "Elevator aileron rudder" << "Elevon" << "Vtail"; m_aircraft->fixedWingType->addItems(fixedWingTypes); @@ -135,7 +108,17 @@ void ConfigFixedWingWidget::setupUI(QString frameType) { Q_ASSERT(m_aircraft); + // This had to be moved from ConfigFixedWingWidget() here since m_aircraft->fixedWingType->currentText() + // did not seem to work properly to choose alternate .svg files. + QSvgRenderer *renderer = new QSvgRenderer(); + renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); + plane = new QGraphicsSvgItem(); + plane->setSharedRenderer(renderer); + + qDebug() << "Current Aircraft type: \n" << m_aircraft->fixedWingType->currentText(); + if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") { + plane->setElementId("aileron"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevator aileron rudder")); m_aircraft->fwRudder1ChannelBox->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true); @@ -152,6 +135,7 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->elevonSlider1->setEnabled(false); m_aircraft->elevonSlider2->setEnabled(false); } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { + plane->setElementId("aileron"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); m_aircraft->fwAileron1Label->setText("Elevon 1"); m_aircraft->fwAileron2Label->setText("Elevon 2"); @@ -168,6 +152,7 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->elevonSlider1->setEnabled(true); m_aircraft->elevonSlider2->setEnabled(true); } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { + plane->setElementId("vtail"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail")); m_aircraft->fwRudder1ChannelBox->setEnabled(false); m_aircraft->fwRudder2ChannelBox->setEnabled(false); @@ -186,6 +171,12 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->elevonSlider1->setEnabled(true); m_aircraft->elevonSlider2->setEnabled(true); } + + QGraphicsScene *scene = new QGraphicsScene(); + scene->addItem(plane); + scene->setSceneRect(plane->boundingRect()); + m_aircraft->planeShape->setScene(scene); + } void ConfigFixedWingWidget::setupEnabledControls(QString frameType) From 6e5e7e4dd374c5fbe6d5e8e4242f3f5c0bea6d80 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Mon, 16 Dec 2013 20:51:43 -0500 Subject: [PATCH 008/203] Work around for a problem caused by lack of elements in the fixed wing SVG for use in the output window. --- .../config/cfg_vehicletypes/configfixedwingwidget.cpp | 2 +- .../plugins/setupwizard/pages/outputcalibrationpage.cpp | 8 +++----- 2 files changed, 4 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 1c26cc512..f7df0289e 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -135,7 +135,7 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->elevonSlider1->setEnabled(false); m_aircraft->elevonSlider2->setEnabled(false); } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { - plane->setElementId("aileron"); + plane->setElementId("vtail"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); m_aircraft->fwAileron1Label->setText("Elevon 1"); m_aircraft->fwAileron2Label->setText("Elevon 2"); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 1bbd4b4cc..a2963dfac 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -147,8 +147,7 @@ void OutputCalibrationPage::setupVehicle() ui->vehicleView->setScene(m_vehicleScene); } qDebug() << "no clue what a wizard index is!"; -// m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; - m_wizardIndexes << 0 << 1 << 1 << 1 << 2 << 3 << 4; + m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; m_vehicleElementIds << "fixed-aileron" << "aileron"; m_vehicleHighlightElementIndexes << 0 << 1; m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; @@ -161,8 +160,7 @@ void OutputCalibrationPage::setupVehicle() ui->vehicleView->setScene(m_vehicleScene); } qDebug() << "no clue what a wizard index is!"; -// m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; - m_wizardIndexes << 0 << 1 << 1 << 1 << 2 << 3 << 4; + m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; m_vehicleElementIds << "fixed-vtail" << "vtail"; m_vehicleHighlightElementIndexes << 0 << 1; m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; @@ -255,7 +253,7 @@ void OutputCalibrationPage::setWizardPage() ui->servoMaxAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMax); } } - setupVehicleHighlightedPart(); + // setupVehicleHighlightedPart(); // turn this off for now, need to fix fixedwing image elements } void OutputCalibrationPage::initializePage() From 9e417f5ee5909e0b9616cd1c138912543a695a63 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Wed, 18 Dec 2013 12:57:35 -0500 Subject: [PATCH 009/203] Remove some redundant "elevon" stuff for now. Will come back later when proper "elevon + rudder" artwork exists. Currently no different from vtail anyway... Enabled proper channel mixing settings inside the FixedWing wizard Output configuration screen. Attempt to set GUIConfigDataUnion to fixedwing --- .../configfixedwingwidget.cpp | 130 +----------------- .../cfg_vehicletypes/configfixedwingwidget.h | 1 - .../config/configvehicletypewidget.cpp | 7 +- .../setupwizard/pages/fixedwingpage.cpp | 6 +- .../pages/outputcalibrationpage.cpp | 37 ++++- .../vehicleconfigurationhelper.cpp | 120 +++++----------- .../setupwizard/vehicleconfigurationhelper.h | 1 - 7 files changed, 78 insertions(+), 224 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index f7df0289e..71861c2c4 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -86,7 +86,7 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : populateChannelComboBoxes(); QStringList fixedWingTypes; - fixedWingTypes << "Elevator aileron rudder" << "Elevon" << "Vtail"; + fixedWingTypes << "Elevator aileron rudder" << "Vtail"; m_aircraft->fixedWingType->addItems(fixedWingTypes); // Set default model to "Elevator aileron rudder" @@ -134,23 +134,6 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->elevonSlider1->setEnabled(false); m_aircraft->elevonSlider2->setEnabled(false); - } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { - plane->setElementId("vtail"); - setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); - m_aircraft->fwAileron1Label->setText("Elevon 1"); - m_aircraft->fwAileron2Label->setText("Elevon 2"); - m_aircraft->fwElevator1ChannelBox->setEnabled(false); - m_aircraft->fwElevator2ChannelBox->setEnabled(false); - m_aircraft->fwRudder1ChannelBox->setEnabled(true); - m_aircraft->fwRudder2ChannelBox->setEnabled(true); - - m_aircraft->fwElevator1Label->setText("Elevator 1"); - m_aircraft->fwElevator2Label->setText("Elevator 2"); - m_aircraft->elevonLabel1->setText("Roll"); - m_aircraft->elevonLabel2->setText("Pitch"); - - m_aircraft->elevonSlider1->setEnabled(true); - m_aircraft->elevonSlider2->setEnabled(true); } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { plane->setElementId("vtail"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail")); @@ -192,7 +175,7 @@ void ConfigFixedWingWidget::setupEnabledControls(QString frameType) } } - if (frameType == "Vtail" || frameType == "Elevon") { + if (frameType == "Vtail" || frameType == "vtail") { enableComboBoxes(this, CHANNELBOXNAME, 3, true); } else if (frameType == "aileron" || frameType == "Elevator aileron rudder") { enableComboBoxes(this, CHANNELBOXNAME, 4, true); @@ -263,18 +246,9 @@ void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType) setComboCurrentIndex(m_aircraft->fwRudder1ChannelBox, fixed.FixedWingYaw1); setComboCurrentIndex(m_aircraft->fwRudder2ChannelBox, fixed.FixedWingYaw2); - if (frameType == "FixedWingElevon") { - // If the airframe is elevon, restore the slider setting + if (frameType == "FixedWingVtail") { + // If the airframe is vtail, restore the slider setting // Find the channel number for Elevon1 (FixedWingRoll1) - int channel = m_aircraft->fwAileron1ChannelBox->currentIndex() - 1; - if (channel > -1) { - // If for some reason the actuators were incoherent, we might fail here, hence the check. - m_aircraft->elevonSlider1->setValue( - getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL) * 100); - m_aircraft->elevonSlider2->setValue( - getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH) * 100); - } - } else if (frameType == "FixedWingVtail") { int channel = m_aircraft->fwElevator1ChannelBox->currentIndex() - 1; if (channel > -1) { // If for some reason the actuators were incoherent, we might fail here, hence the check. @@ -308,10 +282,7 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() if (m_aircraft->fixedWingType->currentText() == "Elevator aileron rudder") { airframeType = "FixedWing"; setupFrameFixedWing(airframeType); - } else if (m_aircraft->fixedWingType->currentText() == "Elevon") { - airframeType = "FixedWingElevon"; - setupFrameElevon(airframeType); - } else { // "Vtail" + } else if (m_aircraft->fixedWingType->currentText() == "vtail") { airframeType = "FixedWingVtail"; setupFrameVtail(airframeType); } @@ -404,76 +375,6 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType) return true; } -/** - Setup Elevon - */ -bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) -{ - // Check coherence: - // Show any config errors in GUI - if (throwConfigError(airframeType)) { - return false; - } - - GUIConfigDataUnion config = getConfigData(); - resetActuators(&config); - - config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); - config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex(); - config.fixedwing.FixedWingYaw1 = m_aircraft->fwRudder1ChannelBox->currentIndex(); - config.fixedwing.FixedWingYaw2 = m_aircraft->fwRudder2ChannelBox->currentIndex(); - config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex(); - - setConfigData(config); - - UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - Q_ASSERT(mixer); - resetMotorAndServoMixers(mixer); - - // Save the curve: - // ... and compute the matrix: - // In order to make code a bit nicer, we assume: - // - Channel dropdowns start with 'None', then 0 to 7 - - // 1. Assign the servo/motor/none for each channel - - double value; - - // motor - int channel = m_aircraft->fwEngineChannelBox->currentIndex() - 1; - setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); - - // rudders - channel = m_aircraft->fwRudder1ChannelBox->currentIndex() - 1; - setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); - - channel = m_aircraft->fwRudder2ChannelBox->currentIndex() - 1; - setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127); - - // ailerons - channel = m_aircraft->fwAileron1ChannelBox->currentIndex() - 1; - if (channel > -1) { - setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - value = (double)(m_aircraft->elevonSlider2->value() * 1.27); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); - value = (double)(m_aircraft->elevonSlider1->value() * 1.27); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, value); - - channel = m_aircraft->fwAileron2ChannelBox->currentIndex() - 1; - setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - value = (double)(m_aircraft->elevonSlider2->value() * 1.27); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); - value = (double)(m_aircraft->elevonSlider1->value() * 1.27); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -value); - } - - m_aircraft->fwStatusLabel->setText("Mixer generated"); - return true; -} - /** Setup VTail */ @@ -592,27 +493,6 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) m_aircraft->fwAileron1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes m_aircraft->fwRudder1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } - } else if (airframeType == "FixedWingElevon") { - if (m_aircraft->fwEngineChannelBox->currentText() == "None") { - m_aircraft->fwEngineChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes - error = true; - } else { - m_aircraft->fwEngineChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes - } - - if (m_aircraft->fwAileron1ChannelBox->currentText() == "None") { - m_aircraft->fwAileron1ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes - error = true; - } else { - m_aircraft->fwAileron1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes - } - - if (m_aircraft->fwAileron2ChannelBox->currentText() == "None") { - m_aircraft->fwAileron2ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes - error = true; - } else { - m_aircraft->fwAileron2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes - } } else if (airframeType == "FixedWingVtail") { if (m_aircraft->fwEngineChannelBox->currentText() == "None") { m_aircraft->fwEngineChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index da8ef3839..28126fc26 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -67,7 +67,6 @@ private: virtual void resetActuators(GUIConfigDataUnion *configData); bool setupFrameFixedWing(QString airframeType); - bool setupFrameElevon(QString airframeType); bool setupFrameVtail(QString airframeType); void updateAirframe(QString multiRotorType); diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 0d6d4ee05..2abcc7d4c 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -68,9 +68,11 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions() QStringList channelDesc; switch (systemSettingsData.AirframeType) { case SystemSettings::AIRFRAMETYPE_FIXEDWING: + channelDesc = ConfigFixedWingWidget::getChannelDescriptions(); + break; case SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON: + // do nothing for elevon support for the time being. case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL: - // fixed wing channelDesc = ConfigFixedWingWidget::getChannelDescriptions(); break; case SystemSettings::AIRFRAMETYPE_HELICP: @@ -268,8 +270,7 @@ QString ConfigVehicleTypeWidget::frameCategory(QString frameType) { QString category; - if (frameType == "FixedWing" || frameType == "Elevator aileron rudder" || frameType == "FixedWingElevon" - || frameType == "Elevon" || frameType == "FixedWingVtail" || frameType == "Vtail") { + if (frameType == "FixedWing" || frameType == "Elevator aileron rudder" || frameType == "FixedWingVtail" || frameType == "Vtail") { category = "Fixed Wing"; } else if (frameType == "Tri" || frameType == "Tricopter Y" || frameType == "QuadX" || frameType == "Quad X" || frameType == "QuadP" || frameType == "Quad +" || frameType == "Hexa" || frameType == "Hexacopter" diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index 543da261e..9dd9b9638 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -83,10 +83,10 @@ void FixedWingPage::resizeEvent(QResizeEvent *event) void FixedWingPage::setupFixedWingTypesCombo() { ui->typeCombo->addItem(tr("Aileron, Elevator, Rudder"), SetupWizard::FIXED_WING_AILERON); - m_descriptions << tr("A description for aileron driven fixed wing stuff goes here... "); + m_descriptions << tr("This setup currently expects a traditional 4 channel setup including two ailerons (not connected by Y adapter), an elevator and a rudder. "); - ui->typeCombo->addItem(tr("V-Tail, or Elevon"), SetupWizard::FIXED_WING_VTAIL); - m_descriptions << tr("A description for vtail driven fixed wing stuff goes here... "); + ui->typeCombo->addItem(tr("V-Tail"), SetupWizard::FIXED_WING_VTAIL); + m_descriptions << tr("This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet supported. Setup should include only two elevons, and should explicitly not include a rudder."); } void FixedWingPage::updateAvailableTypes() diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index a2963dfac..f39db1abe 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -147,10 +147,29 @@ void OutputCalibrationPage::setupVehicle() ui->vehicleView->setScene(m_vehicleScene); } qDebug() << "no clue what a wizard index is!"; - m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; + m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1; m_vehicleElementIds << "fixed-aileron" << "aileron"; m_vehicleHighlightElementIndexes << 0 << 1; - m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; + m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4; + + // see Servo city for an example. 1500 usec is center on MS85mg for example. - http://www.servocity.com/html/hs-85mg__mighty_micro.html + // make sure Aileron servo one does not go to an extreme value + m_actuatorSettings[1].channelMin = 1500; + m_actuatorSettings[1].channelNeutral = 1500; + m_actuatorSettings[1].channelMax = 1500; + // make sure Aileron servo two does not go to an extreme value + m_actuatorSettings[2].channelMin = 1500; + m_actuatorSettings[2].channelNeutral = 1500; + m_actuatorSettings[2].channelMax = 1500; + // make sure Elevator servo one does not go to an extreme value + m_actuatorSettings[3].channelMin = 1500; + m_actuatorSettings[4].channelNeutral = 1500; + m_actuatorSettings[3].channelMax = 1500; + // make sure Rudder servo one does not go to an extreme value + m_actuatorSettings[4].channelMin = 1500; + m_actuatorSettings[4].channelNeutral = 1500; + m_actuatorSettings[4].channelMax = 1500; + getWizard()->setActuatorSettings(m_actuatorSettings); break; case SetupWizard::FIXED_WING_VTAIL: @@ -160,10 +179,20 @@ void OutputCalibrationPage::setupVehicle() ui->vehicleView->setScene(m_vehicleScene); } qDebug() << "no clue what a wizard index is!"; - m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; + m_wizardIndexes << 0 << 1 << 1 << 1; m_vehicleElementIds << "fixed-vtail" << "vtail"; m_vehicleHighlightElementIndexes << 0 << 1; - m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; + m_channelIndex << 0 << 0 << 1 << 2; + + // make sure elevon servo one does not go to an extreme value + m_actuatorSettings[1].channelMin = 1500; + m_actuatorSettings[1].channelNeutral = 1500; + m_actuatorSettings[1].channelMax = 1500; + // make sure elevon servo two does not go to an extreme value + m_actuatorSettings[2].channelMin = 1500; + m_actuatorSettings[2].channelNeutral = 1500; + m_actuatorSettings[2].channelMax = 1500; + getWizard()->setActuatorSettings(m_actuatorSettings); break; default: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index e07a614d9..d32d0146a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -219,9 +219,6 @@ void VehicleConfigurationHelper::applyVehicleConfiguration() case VehicleConfigurationSource::FIXED_WING_AILERON: setupAileron(); break; -/* case VehicleConfigurationSource::FIXED_WING_ELEVON: - setupElevon(); - break; */ case VehicleConfigurationSource::FIXED_WING_VTAIL: setupVtail(); break; @@ -1304,7 +1301,6 @@ void VehicleConfigurationHelper::setupOctoCopter() applyMultiGUISettings(frame, guiSettings); } -// This is all wrong... I just copied the Tricopter stuff void VehicleConfigurationHelper::setupVtail() { @@ -1314,41 +1310,32 @@ void VehicleConfigurationHelper::setupVtail() channels[0].type = MIXER_TYPE_MOTOR; channels[0].throttle1 = 100; channels[0].throttle2 = 0; - channels[0].roll = 100; - channels[0].pitch = 50; + channels[0].roll = 0; + channels[0].pitch = 0; channels[0].yaw = 0; - channels[1].type = MIXER_TYPE_MOTOR; - channels[1].throttle1 = 100; + channels[1].type = MIXER_TYPE_SERVO; + channels[1].throttle1 = 0; channels[1].throttle2 = 0; channels[1].roll = -100; channels[1].pitch = 50; channels[1].yaw = 0; - channels[2].type = MIXER_TYPE_MOTOR; - channels[2].throttle1 = 100; + channels[2].type = MIXER_TYPE_SERVO; + channels[2].throttle1 = 0; channels[2].throttle2 = 0; - channels[2].roll = 0; - channels[2].pitch = -100; + channels[2].roll = 100; + channels[2].pitch = -50; channels[2].yaw = 0; - channels[3].type = MIXER_TYPE_SERVO; - channels[3].throttle1 = 0; - channels[3].throttle2 = 0; - channels[3].roll = 0; - channels[3].pitch = 0; - channels[3].yaw = 100; - - guiSettings.multi.VTOLMotorNW = 1; - guiSettings.multi.VTOLMotorNE = 2; - guiSettings.multi.VTOLMotorS = 3; - guiSettings.multi.TRIYaw = 4; + guiSettings.fixedwing.FixedWingThrottle = 1; + guiSettings.fixedwing.FixedWingRoll1 = 2; + guiSettings.fixedwing.FixedWingRoll2 = 3; applyMixerConfiguration(channels); applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL, guiSettings); } -// This is all wrong... I just copied the Tricopter stuff void VehicleConfigurationHelper::setupAileron() { // Typical vehicle setup @@ -1362,24 +1349,31 @@ void VehicleConfigurationHelper::setupAileron() channels[0].type = MIXER_TYPE_MOTOR; channels[0].throttle1 = 100; channels[0].throttle2 = 0; - channels[0].roll = 100; - channels[0].pitch = 50; + channels[0].roll = 0; + channels[0].pitch = 0; channels[0].yaw = 0; - channels[1].type = MIXER_TYPE_MOTOR; - channels[1].throttle1 = 100; + channels[1].type = MIXER_TYPE_SERVO; + channels[1].throttle1 = 0; channels[1].throttle2 = 0; channels[1].roll = -100; - channels[1].pitch = 50; + channels[1].pitch = 0; channels[1].yaw = 0; - channels[2].type = MIXER_TYPE_MOTOR; - channels[2].throttle1 = 100; + channels[2].type = MIXER_TYPE_SERVO; + channels[2].throttle1 = 0; channels[2].throttle2 = 0; - channels[2].roll = 0; - channels[2].pitch = -100; + channels[2].roll = 100; + channels[2].pitch = 0; channels[2].yaw = 0; + channels[3].type = MIXER_TYPE_SERVO; + channels[3].throttle1 = 0; + channels[3].throttle2 = 0; + channels[3].roll = 0; + channels[3].pitch = 100; + channels[3].yaw = 0; + channels[3].type = MIXER_TYPE_SERVO; channels[3].throttle1 = 0; channels[3].throttle2 = 0; @@ -1387,60 +1381,12 @@ void VehicleConfigurationHelper::setupAileron() channels[3].pitch = 0; channels[3].yaw = 100; - guiSettings.multi.VTOLMotorNW = 1; - guiSettings.multi.VTOLMotorNE = 2; - guiSettings.multi.VTOLMotorS = 3; - guiSettings.multi.TRIYaw = 4; + guiSettings.fixedwing.FixedWingThrottle = 1; + guiSettings.fixedwing.FixedWingRoll1 = 2; + guiSettings.fixedwing.FixedWingRoll2 = 3; + guiSettings.fixedwing.FixedWingPitch1 = 4; + guiSettings.fixedwing.FixedWingYaw1 = 5; applyMixerConfiguration(channels); - applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL, guiSettings); + applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGAILERON, guiSettings); } - -// This is all wrong... I just copied the Tricopter stuff -void VehicleConfigurationHelper::setupElevon() -{ - // Typical vehicle setup - // 1. Setup mixer data - // 2. Setup GUI data - // 3. Apply changes - - mixerChannelSettings channels[10]; - GUIConfigDataUnion guiSettings = getGUIConfigData(); - - channels[0].type = MIXER_TYPE_MOTOR; - channels[0].throttle1 = 100; - channels[0].throttle2 = 0; - channels[0].roll = 100; - channels[0].pitch = 50; - channels[0].yaw = 0; - - channels[1].type = MIXER_TYPE_MOTOR; - channels[1].throttle1 = 100; - channels[1].throttle2 = 0; - channels[1].roll = -100; - channels[1].pitch = 50; - channels[1].yaw = 0; - - channels[2].type = MIXER_TYPE_MOTOR; - channels[2].throttle1 = 100; - channels[2].throttle2 = 0; - channels[2].roll = 0; - channels[2].pitch = -100; - channels[2].yaw = 0; - - channels[3].type = MIXER_TYPE_SERVO; - channels[3].throttle1 = 0; - channels[3].throttle2 = 0; - channels[3].roll = 0; - channels[3].pitch = 0; - channels[3].yaw = 100; - - guiSettings.multi.VTOLMotorNW = 1; - guiSettings.multi.VTOLMotorNE = 2; - guiSettings.multi.VTOLMotorS = 3; - guiSettings.multi.TRIYaw = 4; - - applyMixerConfiguration(channels); - applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON, guiSettings); -} - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h index 197f1a435..d3ef88df4 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h @@ -105,7 +105,6 @@ private: void setupOctoCopter(); void setupVtail(); void setupAileron(); - void setupElevon(); private slots: void uAVOTransactionCompleted(UAVObject *object, bool success); From b6f0e5e3058e65f937f9f89f8e4dade428f76f4a Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Wed, 18 Dec 2013 15:14:56 -0500 Subject: [PATCH 010/203] Sort out issues with servo vs. motor sliders... finally figure out what wizardIndexes are! per OutputCalibrationPage::setWizardPage() --- .../pages/outputcalibrationpage.cpp | 4 ++-- .../setupwizard/vehicleconfigurationhelper.cpp | 18 +++++++++++++++++- 2 files changed, 19 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index f39db1abe..d720f6118 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -147,7 +147,7 @@ void OutputCalibrationPage::setupVehicle() ui->vehicleView->setScene(m_vehicleScene); } qDebug() << "no clue what a wizard index is!"; - m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1; + m_wizardIndexes << 0 << 1 << 2 << 2 << 2 << 2; // These come from OutputCalibrationPage::setWizardPage() m_vehicleElementIds << "fixed-aileron" << "aileron"; m_vehicleHighlightElementIndexes << 0 << 1; m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4; @@ -179,7 +179,7 @@ void OutputCalibrationPage::setupVehicle() ui->vehicleView->setScene(m_vehicleScene); } qDebug() << "no clue what a wizard index is!"; - m_wizardIndexes << 0 << 1 << 1 << 1; + m_wizardIndexes << 0 << 2 << 2 << 2; // These come from OutputCalibrationPage::setWizardPage() m_vehicleElementIds << "fixed-vtail" << "vtail"; m_vehicleHighlightElementIndexes << 0 << 1; m_channelIndex << 0 << 0 << 1 << 2; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index d32d0146a..5de6ae900 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -306,7 +306,23 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() addModifiedObject(actSettings, tr("Writing actuator settings")); break; } +/* case VehicleConfigurationSource::VEHICLE_FIXEDWING: + { + ActuatorSettings::DataFields data = actSettings->getData(); + + qDebug() << "Override center pulse for fixed wing servos\n"; + // move all but first chan to 1500 center pluse + QList actuatorSettings = m_configSource->getActuatorSettings(); + for (quint16 i = 1; i < ActuatorSettings::CHANNELMAX_NUMELEM; i++) { + data.ChannelType[i] = ActuatorSettings::CHANNELTYPE_PWM; + data.ChannelAddr[i] = i; + data.ChannelMin[i] = 1500; + data.ChannelNeutral[i] = 1500; + data.ChannelMax[i] = 1500; + } + } +*/ case VehicleConfigurationSource::VEHICLE_HELI: case VehicleConfigurationSource::VEHICLE_SURFACE: // TODO: Implement settings for other vehicle types? @@ -1388,5 +1404,5 @@ void VehicleConfigurationHelper::setupAileron() guiSettings.fixedwing.FixedWingYaw1 = 5; applyMixerConfiguration(channels); - applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGAILERON, guiSettings); + applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWING, guiSettings); } From 33d963d24e42964e83a93a651f291869296c1bc5 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Wed, 18 Dec 2013 16:41:38 -0500 Subject: [PATCH 011/203] prepping to fix refreshWidgetsValues() so that Output & Vehicle screens populate properly after wizard is run. --- .../configfixedwingwidget.cpp | 29 ++++++++++--------- .../pages/outputcalibrationpage.cpp | 4 +-- 2 files changed, 17 insertions(+), 16 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 71861c2c4..72eaf436c 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -53,27 +53,28 @@ QStringList ConfigFixedWingWidget::getChannelDescriptions() // get the gui config data GUIConfigDataUnion configData = getConfigData(); + fixedGUISettingsStruct fixed = configData.fixedwing; - if (configData.fixedwing.FixedWingPitch1 > 0) { - channelDesc[configData.fixedwing.FixedWingPitch1 - 1] = QString("FixedWingPitch1"); + if (fixed.FixedWingThrottle > 0 && fixed.FixedWingThrottle <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { + channelDesc[fixed.FixedWingThrottle - 1] = QString("fixed.WingThrottle"); } - if (configData.fixedwing.FixedWingPitch2 > 0) { - channelDesc[configData.fixedwing.FixedWingPitch2 - 1] = QString("FixedWingPitch2"); + if (fixed.FixedWingPitch1 > 0 && fixed.FixedWingPitch1 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { + channelDesc[fixed.FixedWingPitch1 - 1] = QString("FixedWingPitch1"); } - if (configData.fixedwing.FixedWingRoll1 > 0) { - channelDesc[configData.fixedwing.FixedWingRoll1 - 1] = QString("FixedWingRoll1"); + if (fixed.FixedWingPitch2 > 0 && fixed.FixedWingPitch2 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { + channelDesc[fixed.FixedWingPitch2 - 1] = QString("FixedWingPitch2"); } - if (configData.fixedwing.FixedWingRoll2 > 0) { - channelDesc[configData.fixedwing.FixedWingRoll2 - 1] = QString("FixedWingRoll2"); + if (fixed.FixedWingRoll1 > 0 && fixed.FixedWingRoll1 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { + channelDesc[fixed.FixedWingRoll1 - 1] = QString("FixedWingRoll1"); } - if (configData.fixedwing.FixedWingYaw1 > 0) { - channelDesc[configData.fixedwing.FixedWingYaw1 - 1] = QString("FixedWingYaw1"); + if (fixed.FixedWingRoll2 > 0 && fixed.FixedWingRoll2 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { + channelDesc[fixed.FixedWingRoll2 - 1] = QString("FixedWingRoll2"); } - if (configData.fixedwing.FixedWingYaw2 > 0) { - channelDesc[configData.fixedwing.FixedWingYaw2 - 1] = QString("FixedWingYaw2"); + if (fixed.FixedWingYaw1 > 0 && fixed.FixedWingYaw1 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { + channelDesc[fixed.FixedWingYaw1 - 1] = QString("FixedWingYaw1"); } - if (configData.fixedwing.FixedWingThrottle > 0) { - channelDesc[configData.fixedwing.FixedWingThrottle - 1] = QString("FixedWingThrottle"); + if (fixed.FixedWingYaw2 > 0 && fixed.FixedWingYaw2 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { + channelDesc[fixed.FixedWingYaw2 - 1] = QString("FixedWingYaw2"); } return channelDesc; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index d720f6118..edb4419c9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -147,7 +147,7 @@ void OutputCalibrationPage::setupVehicle() ui->vehicleView->setScene(m_vehicleScene); } qDebug() << "no clue what a wizard index is!"; - m_wizardIndexes << 0 << 1 << 2 << 2 << 2 << 2; // These come from OutputCalibrationPage::setWizardPage() + m_wizardIndexes << 0 << 1 << 3 << 3 << 3 << 3; // These come from OutputCalibrationPage::setWizardPage() m_vehicleElementIds << "fixed-aileron" << "aileron"; m_vehicleHighlightElementIndexes << 0 << 1; m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4; @@ -179,7 +179,7 @@ void OutputCalibrationPage::setupVehicle() ui->vehicleView->setScene(m_vehicleScene); } qDebug() << "no clue what a wizard index is!"; - m_wizardIndexes << 0 << 2 << 2 << 2; // These come from OutputCalibrationPage::setWizardPage() + m_wizardIndexes << 0 << 0 << 3 << 3; // These come from OutputCalibrationPage::setWizardPage() m_vehicleElementIds << "fixed-vtail" << "vtail"; m_vehicleHighlightElementIndexes << 0 << 1; m_channelIndex << 0 << 0 << 1 << 2; From de9a30e4242e7656bdc23b48adb66eddd32987b2 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Wed, 18 Dec 2013 17:16:12 -0500 Subject: [PATCH 012/203] prepping to fix refreshWidgetValues(0 all the setComboCurrentIndex() calls are missing. --- .../cfg_vehicletypes/configfixedwingwidget.cpp | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 72eaf436c..24f93339a 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -56,7 +56,7 @@ QStringList ConfigFixedWingWidget::getChannelDescriptions() fixedGUISettingsStruct fixed = configData.fixedwing; if (fixed.FixedWingThrottle > 0 && fixed.FixedWingThrottle <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingThrottle - 1] = QString("fixed.WingThrottle"); + channelDesc[fixed.FixedWingThrottle - 1] = QString("WingThrottle"); } if (fixed.FixedWingPitch1 > 0 && fixed.FixedWingPitch1 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { channelDesc[fixed.FixedWingPitch1 - 1] = QString("FixedWingPitch1"); @@ -91,10 +91,13 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : m_aircraft->fixedWingType->addItems(fixedWingTypes); // Set default model to "Elevator aileron rudder" - connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); - setupUI(m_aircraft->fixedWingType->currentText()); + // setupUI(m_aircraft->fixedWingType->currentText()); + + connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); + + updateEnableControls(); } ConfigFixedWingWidget::~ConfigFixedWingWidget() @@ -108,9 +111,12 @@ ConfigFixedWingWidget::~ConfigFixedWingWidget() void ConfigFixedWingWidget::setupUI(QString frameType) { Q_ASSERT(m_aircraft); + Q_ASSERT(plane); // This had to be moved from ConfigFixedWingWidget() here since m_aircraft->fixedWingType->currentText() // did not seem to work properly to choose alternate .svg files. + m_aircraft->planeShape->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + m_aircraft->planeShape->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); QSvgRenderer *renderer = new QSvgRenderer(); renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); plane = new QGraphicsSvgItem(); @@ -161,6 +167,9 @@ void ConfigFixedWingWidget::setupUI(QString frameType) scene->setSceneRect(plane->boundingRect()); m_aircraft->planeShape->setScene(scene); + setupEnabledControls(frameType); + // Draw the appropriate airframe + updateAirframe(frameType); } void ConfigFixedWingWidget::setupEnabledControls(QString frameType) From 6ee5baa1467452f5980b2defb11b27dc6b41e283 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Wed, 18 Dec 2013 17:28:25 -0500 Subject: [PATCH 013/203] I was aparantly missing a call to updateAirframe(frameType); --- .../cfg_vehicletypes/configfixedwingwidget.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 24f93339a..a621d1d8a 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -268,6 +268,8 @@ void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType) getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH) * 100); } } + + updateAirframe(frameType); } /** @@ -275,20 +277,15 @@ void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType) */ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() { - QString airframeType = "FixedWing"; - - // Save the curve (common to all Fixed wing frames) UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(mixer); - // Remove Feed Forward, it is pointless on a plane: - setMixerValue(mixer, "FeedForward", 0.0); - // Set the throttle curve setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->fixedWingThrottle->getCurve()); - // All airframe types must start with "FixedWing" + QString airframeType; + if (m_aircraft->fixedWingType->currentText() == "Elevator aileron rudder") { airframeType = "FixedWing"; setupFrameFixedWing(airframeType); @@ -296,6 +293,9 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() airframeType = "FixedWingVtail"; setupFrameVtail(airframeType); } + + // Remove Feed Forward, it is pointless on a plane: + setMixerValue(mixer, "FeedForward", 0.0); return airframeType; } From 3862c9cfaa04849479fd3cca250a062694a0fe40 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Fri, 20 Dec 2013 02:08:08 -0500 Subject: [PATCH 014/203] settings still not saving to the board... trying to sort it out. Making sure all necessary codepaths exist in the FixedWing clone of the MultiRotor code for the Wizard. --- .../configfixedwingwidget.cpp | 114 ++++++++++++++++-- .../cfg_vehicletypes/configfixedwingwidget.h | 2 + .../pages/outputcalibrationpage.cpp | 2 +- 3 files changed, 110 insertions(+), 8 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index a621d1d8a..07ba0a4ba 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -36,6 +36,7 @@ #include #include #include +#include #include #include #include @@ -96,7 +97,6 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : // setupUI(m_aircraft->fixedWingType->currentText()); connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); - updateEnableControls(); } @@ -105,9 +105,6 @@ ConfigFixedWingWidget::~ConfigFixedWingWidget() delete m_aircraft; } -/** - Virtual function to setup the UI - */ void ConfigFixedWingWidget::setupUI(QString frameType) { Q_ASSERT(m_aircraft); @@ -273,7 +270,7 @@ void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType) } /** - Virtual function to update the UI widget objects + Helper function to update the UI widget objects */ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() { @@ -281,17 +278,51 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() Q_ASSERT(mixer); - // Set the throttle curve + // Curve is also common to all quads: setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->fixedWingThrottle->getCurve()); QString airframeType; + QList motor_servo_List; if (m_aircraft->fixedWingType->currentText() == "Elevator aileron rudder") { airframeType = "FixedWing"; setupFrameFixedWing(airframeType); - } else if (m_aircraft->fixedWingType->currentText() == "vtail") { + + motor_servo_List << "FixedWingThrottle" << "FixedWingPitch1" << "FixedWingPitch2" << "FixedWingRoll1" << "FixedWingRoll2" << "FixedWingYaw1" << "FixedWingYaw2"; + setupMotors(motor_servo_List); + + GUIConfigDataUnion config = getConfigData(); + setConfigData(config); + + m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); + + } + else if (m_aircraft->fixedWingType->currentText() == "vtail") { airframeType = "FixedWingVtail"; setupFrameVtail(airframeType); + + motor_servo_List << "FixedWingThrottle" << "FixedWingRoll1" << "FixedWingRoll2"; + setupMotors(motor_servo_List); + + GUIConfigDataUnion config = getConfigData(); + setConfigData(config); + + // Vtail Layout: + // pitch roll yaw + double mixerMatrix[8][3] = { + { 0, 0, 0 }, + { 0, 0, 0 }, + { 0, 0, 0 }, + { 0, 0, 0 }, + { 0, 0, 0 }, + { 0, 0, 0 }, + { 0, 0, 0 }, + { 0, 0, 0 } + }; + setupFixedWingMixer(mixerMatrix); + + m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); + } // Remove Feed Forward, it is pointless on a plane: @@ -300,6 +331,39 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() return airframeType; } +void ConfigFixedWingWidget::setupMotors(QList motorList) +{ + QList mmList; + mmList << m_aircraft->fwEngineChannelBox << m_aircraft->fwAileron1ChannelBox + << m_aircraft->fwAileron2ChannelBox << m_aircraft->fwElevator1ChannelBox + << m_aircraft->fwElevator2ChannelBox << m_aircraft->fwRudder1ChannelBox + << m_aircraft->fwRudder2ChannelBox; + + GUIConfigDataUnion configData = getConfigData(); + resetActuators(&configData); + + foreach(QString motor, motorList) { + int index = mmList.takeFirst()->currentIndex(); + + if (motor == QString("FixedWingThrottle")) { + configData.fixedwing.FixedWingThrottle = index; + } else if (motor == QString("FixedWingPitch1")) { + configData.fixedwing.FixedWingPitch1 = index; + } else if (motor == QString("FixedWingPitch2")) { + configData.fixedwing.FixedWingPitch2 = index; + } else if (motor == QString("FixedWingRoll1")) { + configData.fixedwing.FixedWingRoll1 = index; + } else if (motor == QString("FixedWingRoll2")) { + configData.fixedwing.FixedWingRoll2 = index; + } else if (motor == QString("FixedWingYaw1")) { + configData.fixedwing.FixedWingYaw1 = index; + } else if (motor == QString("FixedWingYaw2")) { + configData.fixedwing.FixedWingYaw1 = index; + } + } + setConfigData(configData); +} + void ConfigFixedWingWidget::updateAirframe(QString frameType) { qDebug() << "ConfigFixedWingWidget::updateAirframe - frame type" << frameType; @@ -334,6 +398,7 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType) config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex(); config.fixedwing.FixedWingYaw1 = m_aircraft->fwRudder1ChannelBox->currentIndex(); + config.fixedwing.FixedWingYaw2 = m_aircraft->fwRudder2ChannelBox->currentIndex(); config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex(); setConfigData(config); @@ -464,6 +529,41 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType) return true; } +/** + This function sets up the vtail fixed wing mixer values. + */ +bool ConfigFixedWingWidget::setupFixedWingMixer(double mixerFactors[8][3]) +{ + UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + + Q_ASSERT(mixer); + resetMotorAndServoMixers(mixer); + + // and enable only the relevant channels: +// double pFactor = (double)m_aircraft->fwPitchMixLevel->value() / 100.0; +// double rFactor = (double)m_aircraft->fwRollMixLevel->value() / 100.0; + //invertMotors = m_aircraft->MultirotorRevMixerCheckBox->isChecked(); +// double yFactor = (double)m_aircraft->fwYawMixLevel->value() / 100.0; + + QList mmList; + mmList << m_aircraft->fwEngineChannelBox << m_aircraft->fwAileron1ChannelBox + << m_aircraft->fwAileron2ChannelBox << m_aircraft->fwElevator1ChannelBox + << m_aircraft->fwElevator2ChannelBox << m_aircraft->fwRudder1ChannelBox + << m_aircraft->fwRudder2ChannelBox; + + for (int i = 0; i < 8; i++) { + if (mmList.at(i)->isEnabled()) { + int channel = mmList.at(i)->currentIndex() - 1; + if (channel > -1) { + qDebug() << "code needs to be written here!"; +// setupQuadMotor(channel, mixerFactors[i][0] * pFactor, rFactor * mixerFactors[i][1], +// yFactor * mixerFactors[i][2]); + } + } + } + return true; +} + /** This function displays text and color formatting in order to help the user understand what channels have not yet been configured. */ diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index 28126fc26..6c6bc7bab 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -68,6 +68,8 @@ private: bool setupFrameFixedWing(QString airframeType); bool setupFrameVtail(QString airframeType); + bool setupFixedWingMixer(double mixerFactors[8][3]); + void setupMotors(QList motorList); void updateAirframe(QString multiRotorType); void setupEnabledControls(QString airframeType); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index edb4419c9..c469fa2cc 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -179,7 +179,7 @@ void OutputCalibrationPage::setupVehicle() ui->vehicleView->setScene(m_vehicleScene); } qDebug() << "no clue what a wizard index is!"; - m_wizardIndexes << 0 << 0 << 3 << 3; // These come from OutputCalibrationPage::setWizardPage() + m_wizardIndexes << 0 << 1 << 3 << 3; // These come from OutputCalibrationPage::setWizardPage() m_vehicleElementIds << "fixed-vtail" << "vtail"; m_vehicleHighlightElementIndexes << 0 << 1; m_channelIndex << 0 << 0 << 1 << 2; From a99de5d32661d450cecb14dc5caddbda5d167ff2 Mon Sep 17 00:00:00 2001 From: m_thread Date: Fri, 14 Feb 2014 00:00:52 +0100 Subject: [PATCH 015/203] OP-1222 Fixed svg files. Cleaned up and grouped items to work in wizard. Removed some translations and simplified some gradients. Added support for output calibration of Aileron and v-tail wings. Added comments in the code explaining the various arrays with indexes and ids in the output configuration page class. --- .../config/images/fixedwing-shapes.svg | 4294 +++++-------- .../setupwizard/pages/fixedwingpage.cpp | 2 +- .../pages/outputcalibrationpage.cpp | 100 +- .../setupwizard/pages/outputcalibrationpage.h | 4 + .../pages/outputcalibrationpage.ui | 6 + .../resources/fixedwing-shapes.svg | 5298 ++++++++--------- 6 files changed, 4114 insertions(+), 5590 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index e99a33c65..26045315f 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -19,2771 +19,1531 @@ viewBox="0 0 792 2016" enable-background="new 0 0 792 1008" xml:space="preserve" - inkscape:version="0.48.2 r9819" + inkscape:version="0.48.4 r9939" sodipodi:docname="fixedwing-shapes.svg">image/svg+xml - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + id="metadata4103">image/svg+xml \ No newline at end of file From 4d250ff8566380330f0f5ed79ce0ddcd65d90314 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Sun, 25 May 2014 15:20:04 -0400 Subject: [PATCH 016/203] Fix channel indexes to use servoCenterSlider Set channelNeutral = 1500 where appropriate for each model type. Add the missing actuator save for fixed wing! actSettings->setData(data); --- .../pages/outputcalibrationpage.cpp | 37 +++++++++---------- .../vehicleconfigurationhelper.cpp | 10 +++-- 2 files changed, 24 insertions(+), 23 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 9bfdeba9c..dba143375 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -139,47 +139,46 @@ void OutputCalibrationPage::setupVehicle() break; case SetupWizard::FIXED_WING_AILERON: loadSVGFile(FIXEDWING_SVG_FILE); - m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4; + m_wizardIndexes << 0 << 1 << 2 << 2 << 2 << 2; //2 for servoCenterSlider! m_vehicleElementIds << "aileron" << "aileron-frame" << "aileron-motor" << "aileron-ail-left" << "aileron-ail-right" << "aileron-rudder" << "aileron-elevator"; - m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3 << 4 << 4 << 4 << 5 << 5 << 5; - m_channelIndex << 0 << 0 << 1 << 1 << 1 << 2 << 2 << 2 << 3 << 3 << 3 << 4 << 4 << 4; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5; + m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4; // see Servo city for an example. 1500 usec is center on MS85mg for example. // - http://www.servocity.com/html/hs-85mg__mighty_micro.html // make sure Aileron servo one does not go to an extreme value - m_actuatorSettings[1].channelMin = 1500; + // would also be nice to make these all default to 50hz so we don't shred servos. + m_actuatorSettings[1].channelNeutral = 1500; - m_actuatorSettings[1].channelMax = 1500; // make sure Aileron servo two does not go to an extreme value - m_actuatorSettings[2].channelMin = 1500; m_actuatorSettings[2].channelNeutral = 1500; - m_actuatorSettings[2].channelMax = 1500; // make sure Elevator servo one does not go to an extreme value - m_actuatorSettings[3].channelMin = 1500; - m_actuatorSettings[4].channelNeutral = 1500; - m_actuatorSettings[3].channelMax = 1500; + m_actuatorSettings[3].channelNeutral = 1500; // make sure Rudder servo one does not go to an extreme value - m_actuatorSettings[4].channelMin = 1500; m_actuatorSettings[4].channelNeutral = 1500; - m_actuatorSettings[4].channelMax = 1500; + m_actuatorSettings[4].channelNeutral = 1500; + m_actuatorSettings[5].channelNeutral = 1500; + m_actuatorSettings[6].channelNeutral = 1500; + m_actuatorSettings[7].channelNeutral = 1500; getWizard()->setActuatorSettings(m_actuatorSettings); break; case SetupWizard::FIXED_WING_VTAIL: loadSVGFile(FIXEDWING_SVG_FILE); - m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4; + m_wizardIndexes << 0 << 1 << 2 << 2; //2 for servoCenterSlider! m_vehicleElementIds << "v-tail" << "v-tail-frame" << "v-tail-motor" << "v-tail-elevon-left" << "v-tail-elevon-right"; - m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3; - m_channelIndex << 0 << 0 << 1 << 1 << 1 << 2 << 2 << 2; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3; + m_channelIndex << 0 << 0 << 1 << 2; // make sure elevon servo one does not go to an extreme value - m_actuatorSettings[1].channelMin = 1500; m_actuatorSettings[1].channelNeutral = 1500; - m_actuatorSettings[1].channelMax = 1500; // make sure elevon servo two does not go to an extreme value - m_actuatorSettings[2].channelMin = 1500; m_actuatorSettings[2].channelNeutral = 1500; - m_actuatorSettings[2].channelMax = 1500; + m_actuatorSettings[3].channelNeutral = 1500; + m_actuatorSettings[4].channelNeutral = 1500; + m_actuatorSettings[5].channelNeutral = 1500; + m_actuatorSettings[6].channelNeutral = 1500; + m_actuatorSettings[7].channelNeutral = 1500; getWizard()->setActuatorSettings(m_actuatorSettings); break; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 5de6ae900..ed8969589 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -306,7 +306,7 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() addModifiedObject(actSettings, tr("Writing actuator settings")); break; } -/* + case VehicleConfigurationSource::VEHICLE_FIXEDWING: { ActuatorSettings::DataFields data = actSettings->getData(); @@ -317,12 +317,14 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() for (quint16 i = 1; i < ActuatorSettings::CHANNELMAX_NUMELEM; i++) { data.ChannelType[i] = ActuatorSettings::CHANNELTYPE_PWM; data.ChannelAddr[i] = i; - data.ChannelMin[i] = 1500; data.ChannelNeutral[i] = 1500; - data.ChannelMax[i] = 1500; } + qDebug() << "Save Fixed Wing Actuator Data\n"; + actSettings->setData(data); + addModifiedObject(actSettings, tr("Writing actuator settings")); + break; } -*/ + case VehicleConfigurationSource::VEHICLE_HELI: case VehicleConfigurationSource::VEHICLE_SURFACE: // TODO: Implement settings for other vehicle types? From 4ebaa6f20536a694a13b25d61d6b471cc8fd4072 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Sun, 25 May 2014 16:05:13 -0400 Subject: [PATCH 017/203] set all the min and max values to 554 and 2400 per the Arduino servo library fix some cosmetic errors on the debug output fix the Vtail mixer setting that caused channel 4 to go crazy due to being undefined. Servo would sit and shake for no reason. --- .../setupwizard/outputcalibrationutil.cpp | 10 ++--- .../pages/outputcalibrationpage.cpp | 38 ++++++++++++++++++- .../vehicleconfigurationhelper.cpp | 19 +++++++++- 3 files changed, 60 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.cpp b/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.cpp index e75b95b2b..9cbf911fb 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.cpp @@ -52,7 +52,7 @@ void OutputCalibrationUtil::startChannelOutput(quint16 channel, quint16 safeValu m_outputChannel = channel; m_safeValue = safeValue; - qDebug() << "Starting output for channel " << m_outputChannel << "..."; + qDebug() << "Starting output for channel " << m_outputChannel+1 << "..."; ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager); Q_ASSERT(actuatorCommand); @@ -74,17 +74,17 @@ void OutputCalibrationUtil::startChannelOutput(quint16 channel, quint16 safeValu actuatorCommand->setMetadata(metaData); actuatorCommand->updated(); - qDebug() << "Output for channel " << m_outputChannel << " started."; + qDebug() << "Output for channel " << m_outputChannel+1 << " started."; } } void OutputCalibrationUtil::stopChannelOutput() { if (m_outputChannel >= 0) { - qDebug() << "Stopping output for channel " << m_outputChannel << "..."; + qDebug() << "Stopping output for channel " << m_outputChannel+1 << "..."; // Stop output... setChannelOutputValue(m_safeValue); - qDebug() << "Settings output for channel " << m_outputChannel << " to " << m_safeValue; + qDebug() << "Settings output for channel " << m_outputChannel+1 << " to " << m_safeValue; // Restore metadata to what it was before ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager); @@ -93,7 +93,7 @@ void OutputCalibrationUtil::stopChannelOutput() actuatorCommand->setMetadata(m_savedActuatorCommandMetadata); actuatorCommand->updated(); - qDebug() << "Output for channel " << m_outputChannel << " stopped."; + qDebug() << "Output for channel " << m_outputChannel+1 << " stopped."; m_outputChannel = -1; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index dba143375..5f5c9dd9c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -161,6 +161,24 @@ void OutputCalibrationPage::setupVehicle() m_actuatorSettings[6].channelNeutral = 1500; m_actuatorSettings[7].channelNeutral = 1500; + // Arduino library defaults to 554 http://arduino.cc/en/Reference/ServoAttach, + // 600 is for HS85mg - http://www.servocity.com/html/hs-85mg__mighty_micro.html#.U4JEWhapKBU + // Same rules as above from the Arduino *generic* library and the servo city info for the 85mg + m_actuatorSettings[1].channelMin = 554; + m_actuatorSettings[1].channelMax = 2400; + m_actuatorSettings[2].channelMin = 554; + m_actuatorSettings[2].channelMax = 2400; + m_actuatorSettings[3].channelMin = 554; + m_actuatorSettings[3].channelMax = 2400; + m_actuatorSettings[4].channelMin = 554; + m_actuatorSettings[4].channelMax = 2400; + m_actuatorSettings[5].channelMin = 554; + m_actuatorSettings[5].channelMax = 2400; + m_actuatorSettings[6].channelMin = 554; + m_actuatorSettings[6].channelMax = 2400; + m_actuatorSettings[7].channelMin = 554; + m_actuatorSettings[7].channelMax = 2400; + getWizard()->setActuatorSettings(m_actuatorSettings); break; case SetupWizard::FIXED_WING_VTAIL: @@ -180,6 +198,24 @@ void OutputCalibrationPage::setupVehicle() m_actuatorSettings[6].channelNeutral = 1500; m_actuatorSettings[7].channelNeutral = 1500; + // Arduino library defaults to 554 http://arduino.cc/en/Reference/ServoAttach, + // 600 is for HS85mg - http://www.servocity.com/html/hs-85mg__mighty_micro.html#.U4JEWhapKBU + // Same rules as above from the Arduino *generic* library and the servo city info for the 85mg + m_actuatorSettings[1].channelMin = 554; + m_actuatorSettings[1].channelMax = 2400; + m_actuatorSettings[2].channelMin = 554; + m_actuatorSettings[2].channelMax = 2400; + m_actuatorSettings[3].channelMin = 554; + m_actuatorSettings[3].channelMax = 2400; + m_actuatorSettings[4].channelMin = 554; + m_actuatorSettings[4].channelMax = 2400; + m_actuatorSettings[5].channelMin = 554; + m_actuatorSettings[5].channelMax = 2400; + m_actuatorSettings[6].channelMin = 554; + m_actuatorSettings[6].channelMax = 2400; + m_actuatorSettings[7].channelMin = 554; + m_actuatorSettings[7].channelMax = 2400; + getWizard()->setActuatorSettings(m_actuatorSettings); break; default: @@ -255,7 +291,7 @@ void OutputCalibrationPage::setWizardPage() ui->calibrationStack->setCurrentIndex(currentPageIndex); int currentChannel = getCurrentChannel(); - qDebug() << "Current channel: " << currentChannel; + qDebug() << "Current channel: " << currentChannel+1; if (currentChannel >= 0) { if (currentPageIndex == 1) { ui->motorNeutralSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index ed8969589..07341fb94 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -311,13 +311,16 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() { ActuatorSettings::DataFields data = actSettings->getData(); - qDebug() << "Override center pulse for fixed wing servos\n"; + qDebug() << "Override center, min and max pulses for fixed wing servos\n"; // move all but first chan to 1500 center pluse QList actuatorSettings = m_configSource->getActuatorSettings(); for (quint16 i = 1; i < ActuatorSettings::CHANNELMAX_NUMELEM; i++) { data.ChannelType[i] = ActuatorSettings::CHANNELTYPE_PWM; data.ChannelAddr[i] = i; + data.ChannelMin[i] = 554; // Arduino library defaults to 554 http://arduino.cc/en/Reference/ServoAttach, + // 600 is for HS85mg - http://www.servocity.com/html/hs-85mg__mighty_micro.html#.U4JEWhapKBU data.ChannelNeutral[i] = 1500; + data.ChannelMax[i] = 2400; // Same rules as above from the Arduino *generic* library and the servo city info for the 85mg } qDebug() << "Save Fixed Wing Actuator Data\n"; actSettings->setData(data); @@ -1346,6 +1349,20 @@ void VehicleConfigurationHelper::setupVtail() channels[2].pitch = -50; channels[2].yaw = 0; + channels[3].type = MIXER_TYPE_SERVO; + channels[3].throttle1 = 0; + channels[3].throttle2 = 0; + channels[3].roll = 0; + channels[3].pitch = 0; + channels[3].yaw = 0; + + channels[3].type = MIXER_TYPE_SERVO; + channels[3].throttle1 = 0; + channels[3].throttle2 = 0; + channels[3].roll = 0; + channels[3].pitch = 0; + channels[3].yaw = 0; + guiSettings.fixedwing.FixedWingThrottle = 1; guiSettings.fixedwing.FixedWingRoll1 = 2; guiSettings.fixedwing.FixedWingRoll2 = 3; From 11fa414e1a9efd6c32f52d43ca04bd5fef5e5048 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Thu, 29 May 2014 11:51:20 -0400 Subject: [PATCH 018/203] Fix minor cosmetic issue where vtail model was not rendering in the Configuration screen. Edit the Inkscape Object Properties. Likewise adjust fixedwingpage.cpp to be more consistant with the inkscape label. ie 'vtail' vs. 'v-tail' --- .../src/plugins/config/images/fixedwing-shapes.svg | 12 ++++++------ .../src/plugins/setupwizard/pages/fixedwingpage.cpp | 2 +- 2 files changed, 7 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index 26045315f..dc20b635d 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -19,7 +19,7 @@ viewBox="0 0 792 2016" enable-background="new 0 0 792 1008" xml:space="preserve" - inkscape:version="0.48.4 r9939" + inkscape:version="0.48.2 r9819" sodipodi:docname="fixedwing-shapes.svg">image/svg+xml Date: Sat, 7 Jun 2014 22:31:42 -0400 Subject: [PATCH 019/203] Try to fix my Vtail->Elevon naming issue. Attempt to fix Elevon mixer setting defaults --- .../configfixedwingwidget.cpp | 72 +++++++++---------- .../config/images/fixedwing-shapes.svg | 12 ++-- .../setupwizard/pages/fixedwingpage.cpp | 6 +- .../pages/outputcalibrationpage.cpp | 4 +- .../resources/fixedwing-shapes.svg | 40 +++++------ 5 files changed, 63 insertions(+), 71 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 07ba0a4ba..16eb7fa90 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -88,7 +88,7 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : populateChannelComboBoxes(); QStringList fixedWingTypes; - fixedWingTypes << "Elevator aileron rudder" << "Vtail"; + fixedWingTypes << "Elevator aileron rudder" << "Elevon"; m_aircraft->fixedWingType->addItems(fixedWingTypes); // Set default model to "Elevator aileron rudder" @@ -138,16 +138,16 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->elevonSlider1->setEnabled(false); m_aircraft->elevonSlider2->setEnabled(false); - } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { - plane->setElementId("vtail"); - setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail")); + } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { + plane->setElementId("elevon"); + setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); m_aircraft->fwRudder1ChannelBox->setEnabled(false); m_aircraft->fwRudder2ChannelBox->setEnabled(false); - m_aircraft->fwElevator1Label->setText("Vtail 1"); + m_aircraft->fwElevator1Label->setText("Elevon 1"); m_aircraft->fwElevator1ChannelBox->setEnabled(true); - m_aircraft->fwElevator2Label->setText("Vtail 2"); + m_aircraft->fwElevator2Label->setText("Elevon 2"); m_aircraft->fwElevator2ChannelBox->setEnabled(true); m_aircraft->fwAileron1Label->setText("Aileron 1"); @@ -182,7 +182,7 @@ void ConfigFixedWingWidget::setupEnabledControls(QString frameType) } } - if (frameType == "Vtail" || frameType == "vtail") { + if (frameType == "Elevon" || frameType == "elevon") { enableComboBoxes(this, CHANNELBOXNAME, 3, true); } else if (frameType == "aileron" || frameType == "Elevator aileron rudder") { enableComboBoxes(this, CHANNELBOXNAME, 4, true); @@ -253,8 +253,8 @@ void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType) setComboCurrentIndex(m_aircraft->fwRudder1ChannelBox, fixed.FixedWingYaw1); setComboCurrentIndex(m_aircraft->fwRudder2ChannelBox, fixed.FixedWingYaw2); - if (frameType == "FixedWingVtail") { - // If the airframe is vtail, restore the slider setting + if (frameType == "FixedWingElevon") { + // If the airframe is elevon, restore the slider setting // Find the channel number for Elevon1 (FixedWingRoll1) int channel = m_aircraft->fwElevator1ChannelBox->currentIndex() - 1; if (channel > -1) { @@ -297,9 +297,9 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); } - else if (m_aircraft->fixedWingType->currentText() == "vtail") { - airframeType = "FixedWingVtail"; - setupFrameVtail(airframeType); + else if (m_aircraft->fixedWingType->currentText() == "elevon") { + airframeType = "FixedWingElevon"; + setupFrameElevon(airframeType); motor_servo_List << "FixedWingThrottle" << "FixedWingRoll1" << "FixedWingRoll2"; setupMotors(motor_servo_List); @@ -307,7 +307,7 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() GUIConfigDataUnion config = getConfigData(); setConfigData(config); - // Vtail Layout: + // Elevon Layout: // pitch roll yaw double mixerMatrix[8][3] = { { 0, 0, 0 }, @@ -451,9 +451,9 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType) } /** - Setup VTail + Setup Elevon */ -bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType) +bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) { // Check coherence: // Show any config errors in GUI @@ -465,7 +465,7 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType) resetActuators(&config); config.fixedwing.FixedWingPitch1 = m_aircraft->fwElevator1ChannelBox->currentIndex(); - config.fixedwing.FixedWingPitch2 = m_aircraft->fwElevator2ChannelBox->currentIndex(); + config.fixedwing.FixedWingPitch2 = m_aircraft->fwElevator2ChannelBox->currentIndex(); config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex(); config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex(); @@ -483,6 +483,8 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType) // 1. Assign the servo/motor/none for each channel + double value; + // motor int channel = m_aircraft->fwEngineChannelBox->currentIndex() - 1; setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR); @@ -501,36 +503,27 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType) channel = m_aircraft->fwAileron1ChannelBox->currentIndex() - 1; if (channel > -1) { setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127); - - channel = m_aircraft->fwAileron2ChannelBox->currentIndex() - 1; - setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -127); - } - - // vtail - channel = m_aircraft->fwElevator1ChannelBox->currentIndex() - 1; - if (channel > -1) { - setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - double value = (double)(m_aircraft->elevonSlider2->value() * 1.27); + value = (double)(m_aircraft->elevonSlider2->value() * 1.27); setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); value = (double)(m_aircraft->elevonSlider1->value() * 1.27); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, value); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, value); - channel = m_aircraft->fwElevator2ChannelBox->currentIndex() - 1; + + channel = m_aircraft->fwAileron2ChannelBox->currentIndex() - 1; setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); value = (double)(m_aircraft->elevonSlider2->value() * 1.27); setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); value = (double)(m_aircraft->elevonSlider1->value() * 1.27); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -value); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -value); } m_aircraft->fwStatusLabel->setText("Mixer generated"); return true; + } /** - This function sets up the vtail fixed wing mixer values. + This function sets up the elevon fixed wing mixer values. */ bool ConfigFixedWingWidget::setupFixedWingMixer(double mixerFactors[8][3]) { @@ -603,7 +596,7 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) m_aircraft->fwAileron1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes m_aircraft->fwRudder1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } - } else if (airframeType == "FixedWingVtail") { + } else if (airframeType == "FixedWingElevon") { if (m_aircraft->fwEngineChannelBox->currentText() == "None") { m_aircraft->fwEngineChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes error = true; @@ -611,21 +604,20 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) m_aircraft->fwEngineChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } - if (m_aircraft->fwElevator1ChannelBox->currentText() == "None") { - m_aircraft->fwElevator1ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes + if (m_aircraft->fwAileron1ChannelBox->currentText() == "None") { + m_aircraft->fwAileron1ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes error = true; } else { - m_aircraft->fwElevator1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + m_aircraft->fwAileron1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } - if (m_aircraft->fwElevator2ChannelBox->currentText() == "None") { - m_aircraft->fwElevator2ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes + if (m_aircraft->fwAileron2ChannelBox->currentText() == "None") { + m_aircraft->fwAileron2ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes error = true; } else { - m_aircraft->fwElevator2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + m_aircraft->fwAileron2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } } - if (error) { m_aircraft->fwStatusLabel->setText(QString("ERROR: Assign all necessary channels")); } diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index dc20b635d..e518dd1f3 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -1100,14 +1100,14 @@ id="path8516_1_" inkscape:connector-curvature="0" style="fill:none;stroke:#010101;stroke-width:0.69520003;stroke-linecap:round;stroke-linejoin:round" /> \ No newline at end of file + style="fill:none;stroke:#010101;stroke-width:0.69520003;stroke-linecap:round;stroke-linejoin:round" /> diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index 9dd9b9638..f2d8f27ab 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -85,7 +85,7 @@ void FixedWingPage::setupFixedWingTypesCombo() ui->typeCombo->addItem(tr("Aileron, Elevator, Rudder"), SetupWizard::FIXED_WING_AILERON); m_descriptions << tr("This setup currently expects a traditional 4 channel setup including two ailerons (not connected by Y adapter), an elevator and a rudder. "); - ui->typeCombo->addItem(tr("V-Tail"), SetupWizard::FIXED_WING_VTAIL); + ui->typeCombo->addItem(tr("Elevon"), SetupWizard::FIXED_WING_ELEVON); m_descriptions << tr("This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet supported. Setup should include only two elevons, and should explicitly not include a rudder."); } @@ -105,8 +105,8 @@ void FixedWingPage::updateImageAndDescription() case SetupWizard::FIXED_WING_AILERON: elementId = "aileron"; break; - case SetupWizard::FIXED_WING_VTAIL: - elementId = "vtail"; + case SetupWizard::FIXED_WING_ELEVON: + elementId = "elevon"; break; default: elementId = ""; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 5f5c9dd9c..8021bfcdc 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -181,10 +181,10 @@ void OutputCalibrationPage::setupVehicle() getWizard()->setActuatorSettings(m_actuatorSettings); break; - case SetupWizard::FIXED_WING_VTAIL: + case SetupWizard::FIXED_WING_ELEVON: loadSVGFile(FIXEDWING_SVG_FILE); m_wizardIndexes << 0 << 1 << 2 << 2; //2 for servoCenterSlider! - m_vehicleElementIds << "v-tail" << "v-tail-frame" << "v-tail-motor" << "v-tail-elevon-left" << "v-tail-elevon-right"; + m_vehicleElementIds << "elevon" << "elevon-frame" << "elevon-motor" << "elevon-left" << "elevon-right"; m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3; m_channelIndex << 0 << 0 << 1 << 2; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg index b0f5b5aec..0ed305c34 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg @@ -1828,24 +1828,24 @@ id="tspan9117" sodipodi:role="line">4 \ No newline at end of file + id="path3961-7-5" /> From 0fa69ba7892a0d4b335aa00ee638f4d00b19a8cf Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Sat, 7 Jun 2014 22:52:28 -0400 Subject: [PATCH 020/203] add proper header definition for Elevon setup --- .../src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index 56a386daf..cd8fd4611 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -66,7 +66,7 @@ private: virtual void resetActuators(GUIConfigDataUnion *configData); bool setupFrameFixedWing(QString airframeType); - bool setupFrameVtail(QString airframeType); + bool setupFrameElevon(QString airframeType); bool setupFixedWingMixer(double mixerFactors[8][3]); void setupMotors(QList motorList); From 28246cccbe3b362a61a8612b4c1405214cb52a9f Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Sat, 7 Jun 2014 23:04:12 -0400 Subject: [PATCH 021/203] fix remaining headers --- .../src/plugins/setupwizard/connectiondiagram.cpp | 4 ++-- .../src/plugins/setupwizard/setupwizard.cpp | 4 ++-- .../setupwizard/vehicleconfigurationhelper.cpp | 14 +++++++------- .../setupwizard/vehicleconfigurationhelper.h | 2 +- .../setupwizard/vehicleconfigurationsource.h | 2 +- 5 files changed, 13 insertions(+), 13 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp index 7525d5e55..6057098b1 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -122,8 +122,8 @@ void ConnectionDiagram::setupGraphicsScene() case VehicleConfigurationSource::FIXED_WING_AILERON: elementsToShow << "aileron"; break; - case VehicleConfigurationSource::FIXED_WING_VTAIL: - elementsToShow << "vtail"; + case VehicleConfigurationSource::FIXED_WING_ELEVON: + elementsToShow << "elevon"; break; default: break; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 449296f5b..09be733f1 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -236,8 +236,8 @@ QString SetupWizard::getSummaryText() case SetupWizard::FIXED_WING_AILERON: summary.append(tr("Aileron")); break; - case SetupWizard::FIXED_WING_VTAIL: - summary.append(tr("Vtail")); + case SetupWizard::FIXED_WING_ELEVON: + summary.append(tr("Elevon")); break; default: summary.append(tr("Unknown")); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index d5cf4ad5e..97219ada9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -221,8 +221,8 @@ void VehicleConfigurationHelper::applyVehicleConfiguration() case VehicleConfigurationSource::FIXED_WING_AILERON: setupAileron(); break; - case VehicleConfigurationSource::FIXED_WING_VTAIL: - setupVtail(); + case VehicleConfigurationSource::FIXED_WING_ELEVON: + setupElevon(); break; default: break; @@ -1332,7 +1332,7 @@ void VehicleConfigurationHelper::setupOctoCopter() applyMultiGUISettings(frame, guiSettings); } -void VehicleConfigurationHelper::setupVtail() +void VehicleConfigurationHelper::setupElevon() { mixerChannelSettings channels[10]; @@ -1348,15 +1348,15 @@ void VehicleConfigurationHelper::setupVtail() channels[1].type = MIXER_TYPE_SERVO; channels[1].throttle1 = 0; channels[1].throttle2 = 0; - channels[1].roll = -100; - channels[1].pitch = 50; + channels[1].roll = -127; + channels[1].pitch = 127; channels[1].yaw = 0; channels[2].type = MIXER_TYPE_SERVO; channels[2].throttle1 = 0; channels[2].throttle2 = 0; - channels[2].roll = 100; - channels[2].pitch = -50; + channels[2].roll = 127; + channels[2].pitch = -127; channels[2].yaw = 0; channels[3].type = MIXER_TYPE_SERVO; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h index d3ef88df4..7d92bd4ce 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h @@ -103,7 +103,7 @@ private: void setupQuadCopter(); void setupHexaCopter(); void setupOctoCopter(); - void setupVtail(); + void setupElevon(); void setupAileron(); private slots: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 98f06a991..53e0f8736 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -60,7 +60,7 @@ public: enum VEHICLE_SUB_TYPE { MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS, MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, FIXED_WING_AILERON, - FIXED_WING_VTAIL, HELI_CCPM }; + FIXED_WING_ELEVON, HELI_CCPM }; enum ESC_TYPE { ESC_RAPID, ESC_LEGACY, ESC_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN }; From 75585097203190fc8fa373c0bf597aa6e62d7d54 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Sun, 8 Jun 2014 00:00:43 -0400 Subject: [PATCH 022/203] Revert "Fix minor cosmetic issue where vtail model was not rendering in the Configuration screen. Edit the Inkscape Object Properties." This reverts commit 11fa414e1a9efd6c32f52d43ca04bd5fef5e5048. Conflicts: ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp --- .../src/plugins/config/images/fixedwing-shapes.svg | 14 +++++++++----- .../plugins/setupwizard/pages/fixedwingpage.cpp | 5 +++++ 2 files changed, 14 insertions(+), 5 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index e518dd1f3..f08814a7d 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -19,7 +19,7 @@ viewBox="0 0 792 2016" enable-background="new 0 0 792 1008" xml:space="preserve" - inkscape:version="0.48.2 r9819" + inkscape:version="0.48.4 r9939" sodipodi:docname="fixedwing-shapes.svg">image/svg+xml>>>>>> parent of 11fa414... Fix minor cosmetic issue where vtail model was not rendering in the Configuration screen. Edit the Inkscape Object Properties. transform="matrix(0.8,0,0,0.8,78.355285,170.6871)">>>>>>> parent of 11fa414... Fix minor cosmetic issue where vtail model was not rendering in the Configuration screen. Edit the Inkscape Object Properties. break; default: elementId = ""; From b9733363b360f3983d2465800ef154d4c5564ceb Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Wed, 11 Jun 2014 12:23:33 -0400 Subject: [PATCH 023/203] some revision control data is misplaced preventing compile --- .../src/plugins/config/images/fixedwing-shapes.svg | 4 ---- .../src/plugins/setupwizard/pages/fixedwingpage.cpp | 5 ----- 2 files changed, 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index f08814a7d..52d8f72b5 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -1100,11 +1100,7 @@ id="path8516_1_" inkscape:connector-curvature="0" style="fill:none;stroke:#010101;stroke-width:0.69520003;stroke-linecap:round;stroke-linejoin:round" />>>>>>> parent of 11fa414... Fix minor cosmetic issue where vtail model was not rendering in the Configuration screen. Edit the Inkscape Object Properties. transform="matrix(0.8,0,0,0.8,78.355285,170.6871)">>>>>>> parent of 11fa414... Fix minor cosmetic issue where vtail model was not rendering in the Configuration screen. Edit the Inkscape Object Properties. break; default: elementId = ""; From 1f74a782631cff1e7d11c933be75fdf0351111dc Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Wed, 11 Jun 2014 14:41:42 -0400 Subject: [PATCH 024/203] Attempt adding in the proper Mixer setting constructs for Elevon setup. --- .../configfixedwingwidget.cpp | 94 ++++++++++--------- .../cfg_vehicletypes/configfixedwingwidget.h | 2 + .../config/configvehicletypewidget.cpp | 6 +- .../plugins/setupwizard/connectiondiagram.cpp | 3 + .../setupwizard/pages/fixedwingpage.cpp | 3 + .../src/plugins/setupwizard/setupwizard.cpp | 3 + .../vehicleconfigurationhelper.cpp | 5 +- .../setupwizard/vehicleconfigurationhelper.h | 1 + .../setupwizard/vehicleconfigurationsource.h | 2 +- 9 files changed, 71 insertions(+), 48 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 16eb7fa90..21d7fce1b 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -94,7 +94,7 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : // Set default model to "Elevator aileron rudder" m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); - // setupUI(m_aircraft->fixedWingType->currentText()); + setupUI(m_aircraft->fixedWingType->currentText()); connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); updateEnableControls(); @@ -138,6 +138,8 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->elevonSlider1->setEnabled(false); m_aircraft->elevonSlider2->setEnabled(false); + } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { + // do nothing for now } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { plane->setElementId("elevon"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); @@ -152,7 +154,7 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwAileron1Label->setText("Aileron 1"); m_aircraft->fwAileron2Label->setText("Aileron 2"); - m_aircraft->elevonLabel1->setText("Rudder"); + m_aircraft->elevonLabel1->setText("Roll"); m_aircraft->elevonLabel2->setText("Pitch"); m_aircraft->elevonSlider1->setEnabled(true); @@ -182,7 +184,9 @@ void ConfigFixedWingWidget::setupEnabledControls(QString frameType) } } - if (frameType == "Elevon" || frameType == "elevon") { + if (frameType == "Vtail" || frameType == "vtail") { + // enableComboBoxes(this, CHANNELBOXNAME, 3, true); + } else if (frameType == "Elevon" || frameType == "Elevon") { enableComboBoxes(this, CHANNELBOXNAME, 3, true); } else if (frameType == "aileron" || frameType == "Elevator aileron rudder") { enableComboBoxes(this, CHANNELBOXNAME, 4, true); @@ -250,8 +254,6 @@ void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType) setComboCurrentIndex(m_aircraft->fwAileron2ChannelBox, fixed.FixedWingRoll2); setComboCurrentIndex(m_aircraft->fwElevator1ChannelBox, fixed.FixedWingPitch1); setComboCurrentIndex(m_aircraft->fwElevator2ChannelBox, fixed.FixedWingPitch2); - setComboCurrentIndex(m_aircraft->fwRudder1ChannelBox, fixed.FixedWingYaw1); - setComboCurrentIndex(m_aircraft->fwRudder2ChannelBox, fixed.FixedWingYaw2); if (frameType == "FixedWingElevon") { // If the airframe is elevon, restore the slider setting @@ -260,7 +262,7 @@ void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType) if (channel > -1) { // If for some reason the actuators were incoherent, we might fail here, hence the check. m_aircraft->elevonSlider1->setValue( - getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW) * 100); + getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL) * 100); m_aircraft->elevonSlider2->setValue( getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH) * 100); } @@ -319,7 +321,7 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() { 0, 0, 0 }, { 0, 0, 0 } }; - setupFixedWingMixer(mixerMatrix); + setupFixedWingElevonMixer(mixerMatrix); m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); @@ -483,74 +485,77 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) // 1. Assign the servo/motor/none for each channel - double value; - // motor int channel = m_aircraft->fwEngineChannelBox->currentIndex() - 1; setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR); setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); - // rudders - channel = m_aircraft->fwRudder1ChannelBox->currentIndex() - 1; - setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); - - channel = m_aircraft->fwRudder2ChannelBox->currentIndex() - 1; - setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127); - // ailerons channel = m_aircraft->fwAileron1ChannelBox->currentIndex() - 1; if (channel > -1) { setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - value = (double)(m_aircraft->elevonSlider2->value() * 1.27); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); - value = (double)(m_aircraft->elevonSlider1->value() * 1.27); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, value); - + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127); channel = m_aircraft->fwAileron2ChannelBox->currentIndex() - 1; setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - value = (double)(m_aircraft->elevonSlider2->value() * 1.27); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); - value = (double)(m_aircraft->elevonSlider1->value() * 1.27); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -value); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -127); + } + + // elevon + channel = m_aircraft->fwElevator1ChannelBox->currentIndex() - 1; + if (channel > -1) { + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, 127); + + channel = m_aircraft->fwElevator2ChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, -127); } m_aircraft->fwStatusLabel->setText("Mixer generated"); return true; + } /** - This function sets up the elevon fixed wing mixer values. + Helper function: setupElevonServo */ -bool ConfigFixedWingWidget::setupFixedWingMixer(double mixerFactors[8][3]) +void ConfigFixedWingWidget::setupElevonServo(int channel, double pitch, double roll) { UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, roll * 127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, pitch * 127); +} + +/** + This function sets up the elevon fixed wing mixer values. + */ +bool ConfigFixedWingWidget::setupFixedWingElevonMixer(double mixerFactors[8][3]){ + UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); resetMotorAndServoMixers(mixer); // and enable only the relevant channels: -// double pFactor = (double)m_aircraft->fwPitchMixLevel->value() / 100.0; -// double rFactor = (double)m_aircraft->fwRollMixLevel->value() / 100.0; - //invertMotors = m_aircraft->MultirotorRevMixerCheckBox->isChecked(); -// double yFactor = (double)m_aircraft->fwYawMixLevel->value() / 100.0; + double pFactor = (double)m_aircraft->elevonSlider1->value() / 100.0; + double rFactor = (double)m_aircraft->elevonSlider2->value() / 100.0; QList mmList; mmList << m_aircraft->fwEngineChannelBox << m_aircraft->fwAileron1ChannelBox << m_aircraft->fwAileron2ChannelBox << m_aircraft->fwElevator1ChannelBox - << m_aircraft->fwElevator2ChannelBox << m_aircraft->fwRudder1ChannelBox - << m_aircraft->fwRudder2ChannelBox; + << m_aircraft->fwElevator2ChannelBox; for (int i = 0; i < 8; i++) { if (mmList.at(i)->isEnabled()) { int channel = mmList.at(i)->currentIndex() - 1; if (channel > -1) { - qDebug() << "code needs to be written here!"; -// setupQuadMotor(channel, mixerFactors[i][0] * pFactor, rFactor * mixerFactors[i][1], -// yFactor * mixerFactors[i][2]); + setupElevonServo(channel, mixerFactors[i][0] * pFactor, rFactor * mixerFactors[i][1]); } } } @@ -604,20 +609,21 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) m_aircraft->fwEngineChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } - if (m_aircraft->fwAileron1ChannelBox->currentText() == "None") { - m_aircraft->fwAileron1ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes + if (m_aircraft->fwElevator1ChannelBox->currentText() == "None") { + m_aircraft->fwElevator1ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes error = true; } else { - m_aircraft->fwAileron1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + m_aircraft->fwElevator1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } - if (m_aircraft->fwAileron2ChannelBox->currentText() == "None") { - m_aircraft->fwAileron2ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes + if (m_aircraft->fwElevator2ChannelBox->currentText() == "None") { + m_aircraft->fwElevator2ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes error = true; } else { - m_aircraft->fwAileron2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + m_aircraft->fwElevator2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } } + if (error) { m_aircraft->fwStatusLabel->setText(QString("ERROR: Assign all necessary channels")); } diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index cd8fd4611..582420ff0 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -66,8 +66,10 @@ private: virtual void resetActuators(GUIConfigDataUnion *configData); bool setupFrameFixedWing(QString airframeType); + bool setupFrameVtail(QString airframeType); bool setupFrameElevon(QString airframeType); bool setupFixedWingMixer(double mixerFactors[8][3]); + bool setupFixedWingElevonMixer(double mixerFactors[8][3]); void setupMotors(QList motorList); void updateAirframe(QString multiRotorType); diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 318d71051..f36f02550 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -71,10 +71,12 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions() channelDesc = ConfigFixedWingWidget::getChannelDescriptions(); break; case SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON: - // do nothing for elevon support for the time being. - case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL: channelDesc = ConfigFixedWingWidget::getChannelDescriptions(); break; + case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL: + // do nothing for vtail support for the time being. + // channelDesc = ConfigFixedWingWidget::getChannelDescriptions(); + break; case SystemSettings::AIRFRAMETYPE_HELICP: // helicp channelDesc = ConfigCcpmWidget::getChannelDescriptions(); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp index 6057098b1..ac0bedbad 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -125,6 +125,9 @@ void ConnectionDiagram::setupGraphicsScene() case VehicleConfigurationSource::FIXED_WING_ELEVON: elementsToShow << "elevon"; break; + case VehicleConfigurationSource::FIXED_WING_VTAIL: + elementsToShow << "vtail"; + break; default: break; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index f2d8f27ab..cb832267a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -108,6 +108,9 @@ void FixedWingPage::updateImageAndDescription() case SetupWizard::FIXED_WING_ELEVON: elementId = "elevon"; break; +// case SetupWizard::FIXED_WING_VTAIL: +// elementId = "vtail"; +// break; default: elementId = ""; break; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 09be733f1..7fa6c8fa0 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -239,6 +239,9 @@ QString SetupWizard::getSummaryText() case SetupWizard::FIXED_WING_ELEVON: summary.append(tr("Elevon")); break; +// case SetupWizard::FIXED_WING_VTAIL: +// summary.append(tr("Vtail")); +// break; default: summary.append(tr("Unknown")); break; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 97219ada9..4aa3364d8 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -224,6 +224,9 @@ void VehicleConfigurationHelper::applyVehicleConfiguration() case VehicleConfigurationSource::FIXED_WING_ELEVON: setupElevon(); break; + case VehicleConfigurationSource::FIXED_WING_VTAIL: +// setupVtail(); + break; default: break; } @@ -1378,7 +1381,7 @@ void VehicleConfigurationHelper::setupElevon() guiSettings.fixedwing.FixedWingRoll2 = 3; applyMixerConfiguration(channels); - applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL, guiSettings); + applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON, guiSettings); } void VehicleConfigurationHelper::setupAileron() diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h index 7d92bd4ce..7829ac039 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h @@ -103,6 +103,7 @@ private: void setupQuadCopter(); void setupHexaCopter(); void setupOctoCopter(); + void setupVtail(); void setupElevon(); void setupAileron(); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 53e0f8736..8175b4334 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -60,7 +60,7 @@ public: enum VEHICLE_SUB_TYPE { MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS, MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, FIXED_WING_AILERON, - FIXED_WING_ELEVON, HELI_CCPM }; + FIXED_WING_VTAIL, FIXED_WING_ELEVON, HELI_CCPM }; enum ESC_TYPE { ESC_RAPID, ESC_LEGACY, ESC_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN }; From 569209a5108f7e7dbcd0ceb4b01f5c6c2362dc3f Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Wed, 11 Jun 2014 15:20:31 -0400 Subject: [PATCH 025/203] add setupElevonServo function --- .../src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h | 1 + 1 file changed, 1 insertion(+) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index 582420ff0..67048fa53 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -71,6 +71,7 @@ private: bool setupFixedWingMixer(double mixerFactors[8][3]); bool setupFixedWingElevonMixer(double mixerFactors[8][3]); void setupMotors(QList motorList); + void setupElevonServo(int channel, double roll, double pitch); void updateAirframe(QString multiRotorType); void setupEnabledControls(QString airframeType); From 64b2fce3d40a397778364a7291871ff17d84d658 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Wed, 11 Jun 2014 16:02:15 -0400 Subject: [PATCH 026/203] I created some sort of issue in the Output warning highlights. Disable for now. --- .../plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 21d7fce1b..9dad31617 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -94,7 +94,7 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : // Set default model to "Elevator aileron rudder" m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); - setupUI(m_aircraft->fixedWingType->currentText()); + //setupUI(m_aircraft->fixedWingType->currentText()); connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); updateEnableControls(); @@ -602,6 +602,7 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) m_aircraft->fwRudder1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } } else if (airframeType == "FixedWingElevon") { +/* if (m_aircraft->fwEngineChannelBox->currentText() == "None") { m_aircraft->fwEngineChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes error = true; @@ -622,6 +623,7 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) } else { m_aircraft->fwElevator2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } +*/ } if (error) { From 47673f519e7f5730fde42b8d378f142e06b7f1c1 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Wed, 11 Jun 2014 21:25:05 -0400 Subject: [PATCH 027/203] Attempt to set some mixer values --- .../plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 9dad31617..c79a91007 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -313,8 +313,8 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() // pitch roll yaw double mixerMatrix[8][3] = { { 0, 0, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 }, + { 127, -127, 0 }, + { -127, 127, 0 }, { 0, 0, 0 }, { 0, 0, 0 }, { 0, 0, 0 }, From 2dcc9c59f1b207f566ea1702ae9131816af1f773 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Wed, 11 Jun 2014 21:28:20 -0400 Subject: [PATCH 028/203] correct values to be more appropriate for VehicleConfigurationHelper::applyMixerConfiguration() --- .../plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index c79a91007..2fc27cd51 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -313,8 +313,8 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() // pitch roll yaw double mixerMatrix[8][3] = { { 0, 0, 0 }, - { 127, -127, 0 }, - { -127, 127, 0 }, + { 1, -1, 0 }, + { -1, 1, 0 }, { 0, 0, 0 }, { 0, 0, 0 }, { 0, 0, 0 }, From 1bf9f250dc2f38eea57edb94fe3320cc2211e4e0 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Thu, 12 Jun 2014 02:43:38 -0400 Subject: [PATCH 029/203] poor attempt to set some default PIDS? make a note to change the modelview ehre as well. --- .../vehicleconfigurationhelper.cpp | 24 +++++++++++++++++++ 1 file changed, 24 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 4aa3364d8..3968954ff 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -35,6 +35,7 @@ #include "manualcontrolsettings.h" #include "flightmodesettings.h" #include "stabilizationsettings.h" +#include "stabilizationsettingsbank1.h" #include "revocalibration.h" #include "accelgyrosettings.h" @@ -330,6 +331,29 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() qDebug() << "Save Fixed Wing Actuator Data\n"; actSettings->setData(data); addModifiedObject(actSettings, tr("Writing actuator settings")); + + // I think I need to add a saved stabilizationsettings object also. + // unfortunately not sure this is the right way to do it! + + qDebug() << "Save Fixed Wing Default PID Data\n"; + + StabilizationSettingsBank1 *stabilizationSettingsBank = StabilizationSettingsBank1::GetInstance(m_uavoManager); + StabilizationSettingsBank1::DataFields stabSettingsBank = stabilizationSettingsBank->getData(); + stabSettingsBank.RollRatePID[StabilizationSettingsBank1::ROLLRATEPID_KP] = 666; + stabSettingsBank.RollRatePID[StabilizationSettingsBank1::ROLLRATEPID_KI] = 666; + stabSettingsBank.RollPI[StabilizationSettingsBank1::ROLLPI_KP] = 666; + stabSettingsBank.RollPI[StabilizationSettingsBank1::ROLLPI_KI] = 666; + stabSettingsBank.PitchRatePID[StabilizationSettingsBank1::PITCHRATEPID_KP] = 666; + stabSettingsBank.PitchRatePID[StabilizationSettingsBank1::PITCHRATEPID_KI] = 666; + stabSettingsBank.PitchPI[StabilizationSettingsBank1::PITCHPI_KP] = 666; + stabSettingsBank.PitchPI[StabilizationSettingsBank1::PITCHPI_KI] = 666; + + addModifiedObject(stabilizationSettingsBank, tr("Writing stabilization bank 1 settings")); + + // Set up model view image here? + // loop through all the window instances and check which are of the type ModelViewGadget. + // per m_thread on each instance setAcFileName(QString model_file_name) and then call reloadScene() on the same object. + break; } From 9aaa764797ef1356924918e5ff62888b7cfbd0f3 Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Thu, 12 Jun 2014 11:05:46 -0400 Subject: [PATCH 030/203] work out a method to set some default PIDs... using a setData() call helps!!! --- .../vehicleconfigurationhelper.cpp | 31 +++++++++++++------ 1 file changed, 21 insertions(+), 10 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 3968954ff..287727454 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -335,19 +335,30 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() // I think I need to add a saved stabilizationsettings object also. // unfortunately not sure this is the right way to do it! - qDebug() << "Save Fixed Wing Default PID Data\n"; + qDebug() << "Saving Fixed Wing Default PID Data\n"; +// qDebug() << "Save Fixed Wing StabilizationSettings object\n"; +// StabilizationSettings *stabilizationSettings = StabilizationSettings::GetInstance(m_uavoManager); +// StabilizationSettings::DataFields stabSettings = stabilizationSettings->getData(); +// Values pulled from ./build/uavobject-synthetics/gcs/stabilizationsettings.h +// stabSettings.CruiseControlInvertedThrustReversing[StabilizationSettings::CRUISECONTROLINVERTEDTHRUSTREVERSING_UNREVERSED] = 0; +// Currently broken, need to set max servo throw via iLimit here per my notes in http://forums.openpilot.org/topic/32356-gonna-give-revo-a-run-on-my-bixler-v1-any-suggestions/#entry252556 +// stabilizationSettings->setData(stabSettings); +// addModifiedObject(stabilizationSettings, tr("Writing stabilization settings")); + qDebug() << "Save Fixed Wing StabilizationSettingsBank1 object\n"; + +// Values pulled from ./build/uavobject-synthetics/gcs/stabilizationsettingsbank1.h StabilizationSettingsBank1 *stabilizationSettingsBank = StabilizationSettingsBank1::GetInstance(m_uavoManager); StabilizationSettingsBank1::DataFields stabSettingsBank = stabilizationSettingsBank->getData(); - stabSettingsBank.RollRatePID[StabilizationSettingsBank1::ROLLRATEPID_KP] = 666; - stabSettingsBank.RollRatePID[StabilizationSettingsBank1::ROLLRATEPID_KI] = 666; - stabSettingsBank.RollPI[StabilizationSettingsBank1::ROLLPI_KP] = 666; - stabSettingsBank.RollPI[StabilizationSettingsBank1::ROLLPI_KI] = 666; - stabSettingsBank.PitchRatePID[StabilizationSettingsBank1::PITCHRATEPID_KP] = 666; - stabSettingsBank.PitchRatePID[StabilizationSettingsBank1::PITCHRATEPID_KI] = 666; - stabSettingsBank.PitchPI[StabilizationSettingsBank1::PITCHPI_KP] = 666; - stabSettingsBank.PitchPI[StabilizationSettingsBank1::PITCHPI_KI] = 666; - + stabSettingsBank.RollRatePID[StabilizationSettingsBank1::ROLLRATEPID_KP] = 2.420; + stabSettingsBank.RollRatePID[StabilizationSettingsBank1::ROLLRATEPID_KI] = 2.420; + stabSettingsBank.RollPI[StabilizationSettingsBank1::ROLLPI_KP] = 2.420; + stabSettingsBank.RollPI[StabilizationSettingsBank1::ROLLPI_KI] = 2.420; + stabSettingsBank.PitchRatePID[StabilizationSettingsBank1::PITCHRATEPID_KP] = 2.420; + stabSettingsBank.PitchRatePID[StabilizationSettingsBank1::PITCHRATEPID_KI] = 2.420; + stabSettingsBank.PitchPI[StabilizationSettingsBank1::PITCHPI_KP] = 2.420; + stabSettingsBank.PitchPI[StabilizationSettingsBank1::PITCHPI_KI] = 2.420; + stabilizationSettingsBank->setData(stabSettingsBank); addModifiedObject(stabilizationSettingsBank, tr("Writing stabilization bank 1 settings")); // Set up model view image here? From 58dad5d3a5a87171edbad4ca42a2a01b53400ded Mon Sep 17 00:00:00 2001 From: Kevin Finisterre Date: Thu, 12 Jun 2014 12:07:03 -0400 Subject: [PATCH 031/203] Try to set Ilimit Rate... somehow I set Ilimit Attitude instead. Need to sort out. basic idea worked though. --- .../vehicleconfigurationhelper.cpp | 34 ++++++++++++++----- 1 file changed, 25 insertions(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 287727454..d022839d6 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -35,6 +35,7 @@ #include "manualcontrolsettings.h" #include "flightmodesettings.h" #include "stabilizationsettings.h" +#include "stabilizationbank.h" #include "stabilizationsettingsbank1.h" #include "revocalibration.h" #include "accelgyrosettings.h" @@ -336,28 +337,43 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() // unfortunately not sure this is the right way to do it! qDebug() << "Saving Fixed Wing Default PID Data\n"; -// qDebug() << "Save Fixed Wing StabilizationSettings object\n"; -// StabilizationSettings *stabilizationSettings = StabilizationSettings::GetInstance(m_uavoManager); -// StabilizationSettings::DataFields stabSettings = stabilizationSettings->getData(); -// Values pulled from ./build/uavobject-synthetics/gcs/stabilizationsettings.h -// stabSettings.CruiseControlInvertedThrustReversing[StabilizationSettings::CRUISECONTROLINVERTEDTHRUSTREVERSING_UNREVERSED] = 0; -// Currently broken, need to set max servo throw via iLimit here per my notes in http://forums.openpilot.org/topic/32356-gonna-give-revo-a-run-on-my-bixler-v1-any-suggestions/#entry252556 -// stabilizationSettings->setData(stabSettings); -// addModifiedObject(stabilizationSettings, tr("Writing stabilization settings")); + +/* + qDebug() << "Save Fixed Wing StabilizationBank object\n"; + StabilizationBank *stabilizationBank = StabilizationBank::GetInstance(m_uavoManager); + StabilizationBank::DataFields stabBank = stabilizationBank->getData(); + Values pulled from ./build/uavobject-synthetics/gcs/stabilizationbank.h + stabBank.PitchPI[StabilizationBank::PITCHPI_ILIMIT] = 1.123; + stabilizationBank->setData(stabBank); + addModifiedObject(stabilizationBank, tr("Writing stabilization bank")); +*/ qDebug() << "Save Fixed Wing StabilizationSettingsBank1 object\n"; -// Values pulled from ./build/uavobject-synthetics/gcs/stabilizationsettingsbank1.h + // Values pulled from ./build/uavobject-synthetics/gcs/stabilizationsettingsbank1.h StabilizationSettingsBank1 *stabilizationSettingsBank = StabilizationSettingsBank1::GetInstance(m_uavoManager); StabilizationSettingsBank1::DataFields stabSettingsBank = stabilizationSettingsBank->getData(); stabSettingsBank.RollRatePID[StabilizationSettingsBank1::ROLLRATEPID_KP] = 2.420; stabSettingsBank.RollRatePID[StabilizationSettingsBank1::ROLLRATEPID_KI] = 2.420; stabSettingsBank.RollPI[StabilizationSettingsBank1::ROLLPI_KP] = 2.420; stabSettingsBank.RollPI[StabilizationSettingsBank1::ROLLPI_KI] = 2.420; + stabSettingsBank.PitchRatePID[StabilizationSettingsBank1::PITCHRATEPID_KP] = 2.420; stabSettingsBank.PitchRatePID[StabilizationSettingsBank1::PITCHRATEPID_KI] = 2.420; stabSettingsBank.PitchPI[StabilizationSettingsBank1::PITCHPI_KP] = 2.420; stabSettingsBank.PitchPI[StabilizationSettingsBank1::PITCHPI_KI] = 2.420; + + stabSettingsBank.YawRatePID[StabilizationSettingsBank1::YAWRATEPID_KP] = 2.420; + stabSettingsBank.YawRatePID[StabilizationSettingsBank1::YAWRATEPID_KI] = 2.420; + stabSettingsBank.YawPI[StabilizationSettingsBank1::YAWPI_KP] = 2.420; + stabSettingsBank.YawPI[StabilizationSettingsBank1::YAWPI_KI] = 2.420; + + + // need to set max servo throw via iLimit here per my notes in http://forums.openpilot.org/topic/32356-gonna-give-revo-a-run-on-my-bixler-v1-any-suggestions/#entry252556 + stabSettingsBank.PitchPI[StabilizationSettingsBank1::PITCHPI_ILIMIT] = 1.420; + stabSettingsBank.RollPI[StabilizationSettingsBank1::ROLLPI_ILIMIT] = 1.420; + stabSettingsBank.YawPI[StabilizationSettingsBank1::YAWPI_ILIMIT] = 1.420; + stabilizationSettingsBank->setData(stabSettingsBank); addModifiedObject(stabilizationSettingsBank, tr("Writing stabilization bank 1 settings")); From 1f74977472e6ba1ca82c178f7d625fc6cda9f87c Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Tue, 12 Aug 2014 09:44:44 +0200 Subject: [PATCH 032/203] OP-1379 add base types for colour, Initial ext rgb led api definition --- flight/libraries/inc/optypes.h | 61 +++++++++++++++++++++++++++++ flight/libraries/optypes.c | 40 +++++++++++++++++++ flight/pios/common/pios_notify.c | 29 +++++++++++++- flight/pios/inc/pios_notify.h | 50 +++++++++++++++++++++-- flight/pios/inc/pios_ws2811.h | 11 +----- flight/pios/stm32f4xx/pios_ws2811.c | 4 +- make/apps-defs.mk | 1 + 7 files changed, 181 insertions(+), 15 deletions(-) create mode 100644 flight/libraries/inc/optypes.h create mode 100644 flight/libraries/optypes.c diff --git a/flight/libraries/inc/optypes.h b/flight/libraries/inc/optypes.h new file mode 100644 index 000000000..d48e87887 --- /dev/null +++ b/flight/libraries/inc/optypes.h @@ -0,0 +1,61 @@ +/** + ****************************************************************************** + * + * @file optypes.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. + * @brief OP Generic data type library + * -- + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * 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 UTIL_H +#define UTIL_H +#include +typedef struct { + uint8_t R; + uint8_t G; + uint8_t B; +} Color_t; + +extern const Color_t Color_Off; +extern const Color_t Color_Red; +extern const Color_t Color_Lime; +extern const Color_t Color_Blue; +extern const Color_t Color_Yellow; +extern const Color_t Color_Cian; +extern const Color_t Color_Magenta; +extern const Color_t Color_Navy; +extern const Color_t Color_Green; +extern const Color_t Color_Purple; +extern const Color_t Color_Teal; +extern const Color_t Color_Orange; + +#define COLOR_OFF { .R = 0x00, .G = 0x00, .B = 0x00 } +#define COLOR_RED { .R = 0xFF, .G = 0x00, .B = 0x00 } +#define COLOR_LIME { .R = 0x00, .G = 0xFF, .B = 0x00 } +#define COLOR_BLUE { .R = 0x00, .G = 0x00, .B = 0xFF } +#define COLOR_YELLOW { .R = 0xFF, .G = 0xFF, .B = 0x00 } +#define COLOR_CIAN { .R = 0x00, .G = 0xFF, .B = 0xFF } +#define COLOR_MAGENTA { .R = 0xFF, .G = 0x00, .B = 0xFF } +#define COLOR_NAVY { .R = 0x00, .G = 0x00, .B = 0x80 } +#define COLOR_GREEN { .R = 0x00, .G = 0x80, .B = 0x00 } +#define COLOR_PURPLE { .R = 0x80, .G = 0x00, .B = 0x80 } +#define COLOR_TEAL { .R = 0x00, .G = 0x80, .B = 0x80 } +#define COLOR_ORANGE { .R = 0xFF, .G = 0xA5, .B = 0x00 } + +#endif /* UTIL_H */ diff --git a/flight/libraries/optypes.c b/flight/libraries/optypes.c new file mode 100644 index 000000000..a203ee555 --- /dev/null +++ b/flight/libraries/optypes.c @@ -0,0 +1,40 @@ +/** + ****************************************************************************** + * + * @file optypes.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. + * @brief OP Generic data type library + * -- + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * 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 + +const Color_t Color_Off = COLOR_OFF; +const Color_t Color_Red = COLOR_RED; +const Color_t Color_Lime = COLOR_LIME; +const Color_t Color_Blue = COLOR_BLUE; +const Color_t Color_Yellow = COLOR_YELLOW; +const Color_t Color_Cian = COLOR_CIAN; +const Color_t Color_Magenta = COLOR_MAGENTA; +const Color_t Color_Navy = COLOR_NAVY; +const Color_t Color_Green = COLOR_GREEN; +const Color_t Color_Purple = COLOR_PURPLE; +const Color_t Color_Teal = COLOR_TEAL; +const Color_t Color_Orange = COLOR_ORANGE; diff --git a/flight/pios/common/pios_notify.c b/flight/pios/common/pios_notify.c index bf83c22eb..5f47a18a6 100644 --- a/flight/pios/common/pios_notify.c +++ b/flight/pios/common/pios_notify.c @@ -28,7 +28,8 @@ static volatile pios_notify_notification currentNotification = NOTIFY_NONE; static volatile pios_notify_priority currentPriority; - +static volatile ExtLedNotification_t extLedNotification; +static volatile bool newNotification; void PIOS_NOTIFY_StartNotification(pios_notify_notification notification, pios_notify_priority priority) { @@ -47,3 +48,29 @@ pios_notify_notification PIOS_NOTIFY_GetActiveNotification(bool clear) } return ret; } + + +/* + * Play a sequence on the default external led. Sequences with priority higher than NOTIFY_PRIORITY_LOW + * are repeated only once if repeat = -1 + * @param sequence Sequence to be played + * @param priority Priority of the sequence being played + */ +void PIOS_NOTIFICATION_Default_Ext_Led_Play(const LedSequence_t *sequence, pios_notify_priority priority) +{ + extLedNotification.priority = priority; + extLedNotification.sequence = *sequence; + newNotification = true; +} + + +ExtLedNotification_t *PIOS_NOTIFY_GetNewExtLedSequence(bool clear) +{ + if (!newNotification) { + return 0; + } + if (clear) { + newNotification = false; + } + return (ExtLedNotification_t *)&extLedNotification; +} diff --git a/flight/pios/inc/pios_notify.h b/flight/pios/inc/pios_notify.h index 1e800df5c..12daefdc2 100644 --- a/flight/pios/inc/pios_notify.h +++ b/flight/pios/inc/pios_notify.h @@ -26,7 +26,7 @@ #ifndef PIOS_NOTIFY_H_ #define PIOS_NOTIFY_H_ #include - +#include typedef enum { NOTIFY_NONE = 0, NOTIFY_OK, @@ -35,11 +35,35 @@ typedef enum { } pios_notify_notification; typedef enum { - NOTIFY_PRIORITY_CRITICAL = 2, - NOTIFY_PRIORITY_REGULAR = 1, + NOTIFY_PRIORITY_CRITICAL = 2, + NOTIFY_PRIORITY_REGULAR = 1, NOTIFY_PRIORITY_LOW = 0, + NOTIFY_PRIORITY_BACKGROUND = -1, } pios_notify_priority; + +// A single led step, Color, time On/Off, repeat count +#define NOTIFY_SEQUENCE_MAX_STEPS 5 + +typedef struct { + uint16_t time_off; + uint16_t time_on; + Color_t color; + uint8_t repeats; +} LedStep_t; + +typedef struct { + int8_t repeats; // -1 for infinite repetitions + LedStep_t steps[NOTIFY_SEQUENCE_MAX_STEPS]; +} LedSequence_t; + +typedef struct { + LedSequence_t sequence; + pios_notify_priority priority; +} ExtLedNotification_t; + +#define NOTIFY_IS_NULL_STEP(x) (!x || (!x->time_off && !x->time_on && !x->repeats)) + /** * start a new notification. If a notification is active it will be overwritten if its priority is lower than the new one. * The new will be discarded otherwise @@ -55,4 +79,24 @@ void PIOS_NOTIFY_StartNotification(pios_notify_notification notification, pios_n */ pios_notify_notification PIOS_NOTIFY_GetActiveNotification(bool clear); +/* + * Play a sequence on the default external led. Sequences with priority higher than NOTIFY_PRIORITY_LOW + * are repeated only once if repeat = -1 + * @param sequence Sequence to be played + * @param priority Priority of the sequence being played + */ +void PIOS_NOTIFICATION_Default_Ext_Led_Play(const LedSequence_t *sequence, pios_notify_priority priority); + +/* + * Play a sequence on an external rgb led. Sequences with priority higher than NOTIFY_PRIORITY_LOW + * are repeated only once if repeat = -1 + * @param sequence Sequence to be played + * @param ledNumber Led number + * @param priority Priority of the sequence being played + * + */ +// void PIOS_NOTIFICATION_Ext_Led_Play(const LedSequence_t sequence, uint8_t ledNumber, pios_notify_priority priority); + +ExtLedNotification_t *PIOS_NOTIFY_GetNewExtLedSequence(bool clear); + #endif /* PIOS_NOTIFY_H_ */ diff --git a/flight/pios/inc/pios_ws2811.h b/flight/pios/inc/pios_ws2811.h index cb05070ee..6b8778b19 100644 --- a/flight/pios/inc/pios_ws2811.h +++ b/flight/pios/inc/pios_ws2811.h @@ -35,7 +35,7 @@ #include #include #include - +#include #define sign(x) ((x > 0) - (x < 0)) #define PIOS_WS2811_NUMLEDS 2 @@ -106,12 +106,6 @@ typedef uint16_t ledbuf_t; -typedef struct Color Color; -struct Color { - uint8_t R; - uint8_t G; - uint8_t B; -}; struct pios_ws2811_pin_cfg { GPIO_TypeDef *gpio; GPIO_InitTypeDef gpioInit; @@ -139,9 +133,8 @@ struct pios_ws2811_cfg { void PIOS_WS2811_Init(const struct pios_ws2811_cfg *ws2811_cfg, const struct pios_ws2811_pin_cfg *ws2811_pin_cfg); -void PIOS_WS2811_setColorRGB(Color c, uint8_t led, bool update); +void PIOS_WS2811_setColorRGB(Color_t c, uint8_t led, bool update); void PIOS_WS2811_Update(); void PIOS_WS2811_DMA_irq_handler(); - #endif /* PIOS_WS2811_H_ */ diff --git a/flight/pios/stm32f4xx/pios_ws2811.c b/flight/pios/stm32f4xx/pios_ws2811.c index 96719a4a8..f4ffe1bed 100644 --- a/flight/pios/stm32f4xx/pios_ws2811.c +++ b/flight/pios/stm32f4xx/pios_ws2811.c @@ -177,7 +177,7 @@ void PIOS_WS2811_Init(const struct pios_ws2811_cfg *ws2811_cfg, const struct pio fb = (ledbuf_t *)pios_malloc(PIOS_WS2811_BUFFER_SIZE * sizeof(ledbuf_t)); memset(fb, 0, PIOS_WS2811_BUFFER_SIZE * sizeof(ledbuf_t)); - Color ledoff = { 0, 0, 0 }; + const Color_t ledoff = Color_Off; for (uint8_t i = 0; i < PIOS_WS2811_NUMLEDS; i++) { PIOS_WS2811_setColorRGB(ledoff, i, false); } @@ -302,7 +302,7 @@ void setColor(uint8_t color, ledbuf_t *buf) * @param led led number * @param update Perform an update after changing led color */ -void PIOS_WS2811_setColorRGB(Color c, uint8_t led, bool update) +void PIOS_WS2811_setColorRGB(Color_t c, uint8_t led, bool update) { if (led >= PIOS_WS2811_NUMLEDS) { return; diff --git a/make/apps-defs.mk b/make/apps-defs.mk index 72381423e..1c473383c 100644 --- a/make/apps-defs.mk +++ b/make/apps-defs.mk @@ -110,6 +110,7 @@ SRC += $(MATHLIB)/sin_lookup.c SRC += $(MATHLIB)/pid.c SRC += $(MATHLIB)/mathmisc.c SRC += $(FLIGHTLIB)/printf-stdarg.c +SRC += $(FLIGHTLIB)/optypes.c ## Modules SRC += $(foreach mod, $(MODULES), $(sort $(wildcard $(OPMODULEDIR)/$(mod)/*.c))) From fd92fdfadf20b0f5f53b81c867088d8cd32c6808 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Tue, 12 Aug 2014 22:18:36 +0200 Subject: [PATCH 033/203] OP-1379 - initial version of external led sequencer implemented in notification lib. Alert overlay not working yet. --- flight/libraries/inc/notification.h | 1 + flight/libraries/inc/optypes.h | 3 +- flight/libraries/notification.c | 255 +++++++++++++++++++++++++++- flight/libraries/optypes.c | 1 + 4 files changed, 256 insertions(+), 4 deletions(-) diff --git a/flight/libraries/inc/notification.h b/flight/libraries/inc/notification.h index 2053a9609..bcf85015c 100644 --- a/flight/libraries/inc/notification.h +++ b/flight/libraries/inc/notification.h @@ -25,6 +25,7 @@ */ #ifndef NOTIFICATION_H #define NOTIFICATION_H +#include // period of each blink phase #define LED_BLINK_PERIOD_MS 200 diff --git a/flight/libraries/inc/optypes.h b/flight/libraries/inc/optypes.h index d48e87887..82a95e52e 100644 --- a/flight/libraries/inc/optypes.h +++ b/flight/libraries/inc/optypes.h @@ -44,6 +44,7 @@ extern const Color_t Color_Green; extern const Color_t Color_Purple; extern const Color_t Color_Teal; extern const Color_t Color_Orange; +extern const Color_t Color_White; #define COLOR_OFF { .R = 0x00, .G = 0x00, .B = 0x00 } #define COLOR_RED { .R = 0xFF, .G = 0x00, .B = 0x00 } @@ -57,5 +58,5 @@ extern const Color_t Color_Orange; #define COLOR_PURPLE { .R = 0x80, .G = 0x00, .B = 0x80 } #define COLOR_TEAL { .R = 0x00, .G = 0x80, .B = 0x80 } #define COLOR_ORANGE { .R = 0xFF, .G = 0xA5, .B = 0x00 } - +#define COLOR_WHITE { .R = 0xAA, .G = 0xAA, .B = 0xAA } #endif /* UTIL_H */ diff --git a/flight/libraries/notification.c b/flight/libraries/notification.c index 9015e4dd3..c02152e02 100644 --- a/flight/libraries/notification.c +++ b/flight/libraries/notification.c @@ -29,6 +29,41 @@ #include #include #include +#include + +#ifdef PIOS_INCLUDE_WS2811 +#include +#endif +// Private defines +// Maximum number of notifications enqueued when a higher priority notification is added +#define MAX_BACKGROUND_NOTIFICATIONS 3 +#define MAX_HANDLED_LED 1 + +#define BACKGROUND_SEQUENCE -1 +#define RESET_STEP -1 +#define GET_CURRENT_MILLIS (xTaskGetTickCount() * portTICK_RATE_MS) +// Private data types definition + +// this is the status for a single LED notification led set +typedef struct { + int8_t queued_priorities[MAX_BACKGROUND_NOTIFICATIONS]; + LedSequence_t queued_sequences[MAX_BACKGROUND_NOTIFICATIONS]; + LedSequence_t background_sequence; + uint32_t next_run_time; + uint32_t sequence_starting_time; + + int8_t active_sequence_num; // active queued sequence or BACKGROUND_SEQUENCE + bool running; // is this led running? + bool step_phase_on; // true = step on phase, false = step off phase + uint8_t next_sequence_step; // (step number to be executed) << 1 || (0x00 = on phase, 0x01 = off phase) + uint8_t next_step_rep; // next repetition number for next step (valid if step.repeats >1) + uint8_t next_sequence_rep; // next sequence repetition counter (valid if sequence.repeats > 1) + uint8_t led_set; // target led set +} NotifierLedStatus_t; + +#ifdef PIOS_INCLUDE_WS2811 +static bool led_status_initialized = false; +#endif #ifdef PIOS_LED_ALARM #define ALARM_LED_ON() PIOS_LED_On(PIOS_LED_ALARM) @@ -137,6 +172,9 @@ static bool handleAlarms(uint16_t *r_pattern, uint16_t *b_pattern); static bool handleNotifications(pios_notify_notification runningNotification, uint16_t *r_pattern, uint16_t *b_pattern); static void handleFlightMode(uint16_t *r_pattern, uint16_t *b_pattern); static void handleHeartbeat(uint16_t *r_pattern, uint16_t *b_pattern); + +static void HandleExtLeds(); + void NotificationUpdateStatus() { started = true; @@ -150,7 +188,7 @@ void NotificationUpdateStatus() void NotificationOnboardLedsRun() { - static portTickType lastRunTimestamp; + static uint32_t lastRunTimestamp; static uint16_t r_pattern; static uint16_t b_pattern; static uint8_t cycleCount; // count the number of cycles @@ -164,11 +202,13 @@ void NotificationOnboardLedsRun() STATUS_LENGHT } status; - if (!started || (xTaskGetTickCount() - lastRunTimestamp) < (LED_BLINK_PERIOD_MS * portTICK_RATE_MS / 4)) { + HandleExtLeds(); + const uint32_t current_timestamp = GET_CURRENT_MILLIS; + if (!started || (current_timestamp - lastRunTimestamp) < LED_BLINK_PERIOD_MS) { return; } - lastRunTimestamp = xTaskGetTickCount(); + lastRunTimestamp = current_timestamp; // the led will show various status information, subdivided in three phases // - Notification // - Alarm @@ -294,3 +334,212 @@ static void handleHeartbeat(uint16_t *r_pattern, uint16_t *b_pattern) *b_pattern = BLINK_B_HEARTBEAT_PATTERN; *r_pattern = BLINK_R_HEARTBEAT_PATTERN; } + +#ifdef PIOS_INCLUDE_WS2811 + +NotifierLedStatus_t led_status[MAX_HANDLED_LED]; + +static void InitExtLed() +{ + memset(led_status, 0, sizeof(NotifierLedStatus_t) * MAX_HANDLED_LED); + const uint32_t now = GET_CURRENT_MILLIS; + for (uint8_t l = 0; l < MAX_HANDLED_LED; l++) { + led_status[l].led_set = l; + led_status[l].next_run_time = now + 500; // start within half a second + for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { + led_status[l].queued_priorities[i] = NOTIFY_PRIORITY_BACKGROUND; + } + } +} + +/** + * restart current sequence + */ +static void restart_sequence(NotifierLedStatus_t *status, bool immediate) +{ + status->next_sequence_step = 0; + status->next_step_rep = 0; + status->step_phase_on = true; + status->running = true; + if (immediate) { + uint32_t currentTime = GET_CURRENT_MILLIS; + status->next_run_time = currentTime; + } + status->sequence_starting_time = status->next_run_time; +} + +/** + * modify background sequence or enqueue a new sequence to play + */ +static void push_queued_sequence(ExtLedNotification_t *new_notification, NotifierLedStatus_t *status) +{ + int8_t updated_sequence = BACKGROUND_SEQUENCE; + + if (new_notification->priority == NOTIFY_PRIORITY_BACKGROUND) { + status->background_sequence = new_notification->sequence; + } else { + // a notification with priority higher than background. + // try to enqueue it + int8_t insert_point = -1; + int8_t first_free = -1; + for (int8_t i = MAX_BACKGROUND_NOTIFICATIONS; i > -1; i--) { + const int8_t priority_i = status->queued_priorities[i]; + if (priority_i == NOTIFY_PRIORITY_BACKGROUND) { + first_free = i; + insert_point = i; + continue; + } + if (priority_i > new_notification->priority) { + insert_point = i; + } + } + + if (insert_point != first_free) { + // there is a free slot, move everything up one place + if (first_free != -1) { + for (uint8_t i = MAX_BACKGROUND_NOTIFICATIONS - 1; i > insert_point; i--) { + status->queued_priorities[i] = status->queued_priorities[i - 1]; + status->queued_sequences[i] = status->queued_sequences[i - 1]; + } + if (status->active_sequence_num >= insert_point) { + status->active_sequence_num++; + } + } else { + // no free space, discard lowest priority notification and move everything down + for (uint8_t i = 0; i < insert_point; i++) { + status->queued_priorities[i] = status->queued_priorities[i + 1]; + status->queued_sequences[i] = status->queued_sequences[i + 1]; + } + if (status->active_sequence_num <= insert_point) { + status->active_sequence_num--; + } + } + } + + status->queued_priorities[insert_point] = new_notification->priority; + status->queued_sequences[insert_point] = new_notification->sequence; + updated_sequence = insert_point; + } + + if (status->active_sequence_num < updated_sequence) { + status->active_sequence_num = updated_sequence; + restart_sequence(status, true); + } + if (updated_sequence == BACKGROUND_SEQUENCE) { + restart_sequence(status, false); + } +} + +static bool pop_queued_sequence(NotifierLedStatus_t *status) +{ + if (status->active_sequence_num != BACKGROUND_SEQUENCE) { + // start the lower priority item + status->queued_priorities[status->active_sequence_num] = NOTIFY_PRIORITY_BACKGROUND; + status->active_sequence_num--; + return true; + } + // background sequence was completed + return false; +} + +/** + * advance current sequence pointers for next step + */ +static void advance_sequence(NotifierLedStatus_t *status) +{ + LedSequence_t *activeSequence = + status->active_sequence_num == BACKGROUND_SEQUENCE ? + &status->background_sequence : &status->queued_sequences[status->active_sequence_num]; + + uint8_t step = status->next_sequence_step; + LedStep_t *currentStep = &activeSequence->steps[step]; + + // Next step will be the OFF phase, so just update the time and + if (status->step_phase_on) { + // next will be the off phase + status->next_run_time += currentStep->time_on; + status->step_phase_on = false; + // check if off phase should be skipped + if (currentStep->time_off != 0) { + return; + } + } + + // next step is ON phase. check whether to repeat current step or move to next one + status->next_run_time += currentStep->time_off; + status->step_phase_on = true; + + if (status->next_step_rep + 1 < currentStep->repeats) { + // setup next repetition + status->next_step_rep++; + return; + } + + // move to next step + LedStep_t *nextStep = (step + 1 < NOTIFY_SEQUENCE_MAX_STEPS) ? &activeSequence->steps[step + 1] : 0; + + // next step is null, check whether sequence must be repeated or it must move to lower priority queued or background sequences + if (NOTIFY_IS_NULL_STEP(nextStep)) { + if (activeSequence->repeats == -1 || status->next_sequence_rep + 1 < activeSequence->repeats) { + status->next_sequence_rep++; + // restart the sequence + restart_sequence(status, false); + return; + } + if (status->active_sequence_num != BACKGROUND_SEQUENCE) { + // no repeat, pop enqueued or background sequences + pop_queued_sequence(status); + restart_sequence(status, false); + } else { + status->running = false; + } + } else { + status->next_step_rep = 0; + status->next_sequence_step++; + } +} + +/** + * run a led set + */ +static void run_led(NotifierLedStatus_t *status) +{ + uint32_t currentTime = GET_CURRENT_MILLIS; + + if (!status->running || currentTime < status->next_run_time) { + return; + } + status->next_run_time = currentTime; + uint8_t step = status->next_sequence_step; + + LedSequence_t *activeSequence = status->active_sequence_num == BACKGROUND_SEQUENCE ? + &status->background_sequence : &status->queued_sequences[status->active_sequence_num]; + if (status->step_phase_on) { + PIOS_WS2811_setColorRGB(activeSequence->steps[step].color, status->led_set, true); + } else { + PIOS_WS2811_setColorRGB(Color_Off, status->led_set, true); + } + advance_sequence(status); +} + +void HandleExtLeds() +{ + // handle incoming sequences + if (!led_status_initialized) { + InitExtLed(); + led_status_initialized = true; + } + static ExtLedNotification_t *newNotification; + newNotification = PIOS_NOTIFY_GetNewExtLedSequence(true); + if (newNotification) { + push_queued_sequence(newNotification, &led_status[0]); + } + + // Run Leds + for (uint8_t i = 0; i < MAX_HANDLED_LED; i++) { + run_led(&led_status[i]); + } +} +#else /* ifdef PIOS_INCLUDE_WS2811 */ +void HandleExtLeds() {} +#endif /* ifdef PIOS_INCLUDE_WS2811 */ diff --git a/flight/libraries/optypes.c b/flight/libraries/optypes.c index a203ee555..b67b81c3f 100644 --- a/flight/libraries/optypes.c +++ b/flight/libraries/optypes.c @@ -38,3 +38,4 @@ const Color_t Color_Green = COLOR_GREEN; const Color_t Color_Purple = COLOR_PURPLE; const Color_t Color_Teal = COLOR_TEAL; const Color_t Color_Orange = COLOR_ORANGE; +const Color_t Color_White = COLOR_WHITE; From 1067ea59d18bbe7c66a6fdb06917d518aa29c136 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Tue, 12 Aug 2014 22:19:30 +0200 Subject: [PATCH 034/203] OP-1379 - Split pios_ws2811.h in config and public api header --- flight/pios/inc/pios_ws2811.h | 103 +------------ flight/pios/inc/pios_ws2811_cfg.h | 137 ++++++++++++++++++ flight/pios/stm32f4xx/pios_ws2811.c | 2 +- .../boards/discoveryf4bare/board_hw_defs.c | 2 +- .../targets/boards/revolution/board_hw_defs.c | 2 +- 5 files changed, 141 insertions(+), 105 deletions(-) create mode 100644 flight/pios/inc/pios_ws2811_cfg.h diff --git a/flight/pios/inc/pios_ws2811.h b/flight/pios/inc/pios_ws2811.h index 6b8778b19..2d04288a2 100644 --- a/flight/pios/inc/pios_ws2811.h +++ b/flight/pios/inc/pios_ws2811.h @@ -29,112 +29,11 @@ #define PIOS_WS2811_H_ #include -#include -#include -#include -#include -#include -#include #include -#define sign(x) ((x > 0) - (x < 0)) -#define PIOS_WS2811_NUMLEDS 2 -#define PIOS_WS2811_BUFFER_SIZE (((PIOS_WS2811_NUMLEDS) * 24)) -#define PIOS_WS2811_MEMORYDATASIZE DMA_MemoryDataSize_HalfWord -#define PIOS_WS2811_PERIPHERALDATASIZE DMA_PeripheralDataSize_HalfWord -#define PIOS_WS2811_TIM_PERIOD 20 - -// Following times are keept on the lower side to accounts -// for bus contentions and irq response time -#define PIOS_WS2811_T0_HIGH_PERIOD 25 // .35us +/- 150nS -#define PIOS_WS2811_T1_HIGH_PERIOD 60 // .70us +/- 150nS - -#define PIOS_WS2811_DMA_CH1_CONFIG(channel) \ - { \ - .DMA_BufferSize = PIOS_WS2811_BUFFER_SIZE, \ - .DMA_Channel = channel, \ - .DMA_DIR = DMA_DIR_MemoryToPeripheral, \ - .DMA_FIFOMode = DMA_FIFOMode_Enable, \ - .DMA_FIFOThreshold = DMA_FIFOThreshold_HalfFull, \ - .DMA_Memory0BaseAddr = 0, \ - .DMA_MemoryBurst = DMA_MemoryBurst_INC4, \ - .DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \ - .DMA_MemoryInc = DMA_MemoryInc_Enable, \ - .DMA_Mode = DMA_Mode_Circular, \ - .DMA_PeripheralBaseAddr = 0, \ - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \ - .DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \ - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, \ - .DMA_Priority = DMA_Priority_VeryHigh, } - -#define PIOS_WS2811_DMA_CH2_CONFIG(channel) \ - { \ - .DMA_BufferSize = 4, \ - .DMA_Channel = channel, \ - .DMA_DIR = DMA_DIR_MemoryToPeripheral, \ - .DMA_FIFOMode = DMA_FIFOMode_Enable, \ - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, \ - .DMA_Memory0BaseAddr = 0, \ - .DMA_MemoryBurst = DMA_MemoryBurst_INC4, \ - .DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \ - .DMA_MemoryInc = DMA_MemoryInc_Enable, \ - .DMA_Mode = DMA_Mode_Circular, \ - .DMA_PeripheralBaseAddr = 0, \ - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \ - .DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \ - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, \ - .DMA_Priority = DMA_Priority_VeryHigh, } - -#define PIOS_WS2811_DMA_UPDATE_CONFIG(channel) \ - { \ - .DMA_BufferSize = 4, \ - .DMA_Channel = channel, \ - .DMA_DIR = DMA_DIR_MemoryToPeripheral, \ - .DMA_FIFOMode = DMA_FIFOMode_Enable, \ - .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, \ - .DMA_Memory0BaseAddr = 0, \ - .DMA_MemoryBurst = DMA_MemoryBurst_INC4, \ - .DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \ - .DMA_MemoryInc = DMA_MemoryInc_Enable, \ - .DMA_Mode = DMA_Mode_Circular, \ - .DMA_PeripheralBaseAddr = 0, \ - .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \ - .DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \ - .DMA_PeripheralInc = DMA_PeripheralInc_Disable, \ - .DMA_Priority = DMA_Priority_High } - - -typedef uint16_t ledbuf_t; - -struct pios_ws2811_pin_cfg { - GPIO_TypeDef *gpio; - GPIO_InitTypeDef gpioInit; -}; -struct pios_ws2811_cfg { - TIM_TimeBaseInitTypeDef timerInit; - TIM_TypeDef *timer; - uint8_t timerCh1; - uint8_t timerCh2; - - DMA_InitTypeDef dmaInitCh1; - DMA_Stream_TypeDef *streamCh1; - uint32_t dmaItCh1; - - DMA_InitTypeDef dmaInitCh2; - DMA_Stream_TypeDef *streamCh2; - uint32_t dmaItCh2; - - DMA_InitTypeDef dmaInitUpdate; - DMA_Stream_TypeDef *streamUpdate; - uint32_t dmaItUpdate; - uint16_t dmaSource; - struct stm32_irq irq; -}; - -void PIOS_WS2811_Init(const struct pios_ws2811_cfg *ws2811_cfg, const struct pios_ws2811_pin_cfg *ws2811_pin_cfg); +#define PIOS_WS2811_NUMLEDS 2 void PIOS_WS2811_setColorRGB(Color_t c, uint8_t led, bool update); void PIOS_WS2811_Update(); -void PIOS_WS2811_DMA_irq_handler(); #endif /* PIOS_WS2811_H_ */ diff --git a/flight/pios/inc/pios_ws2811_cfg.h b/flight/pios/inc/pios_ws2811_cfg.h new file mode 100644 index 000000000..379df77be --- /dev/null +++ b/flight/pios/inc/pios_ws2811_cfg.h @@ -0,0 +1,137 @@ +/** + ****************************************************************************** + * + * @file pios_ws2811_cfg.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. + * @brief A driver for ws2811 rgb led controller. + * this is a plain PiOS port of the very clever solution + * implemented by Omri Iluz in the chibios driver here: + * https://github.com/omriiluz/WS2812B-LED-Driver-ChibiOS + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * 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 PIOS_WS2811_CFG_H_ +#define PIOS_WS2811_CFG_H_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define sign(x) ((x > 0) - (x < 0)) +#define PIOS_WS2811_BUFFER_SIZE (((PIOS_WS2811_NUMLEDS) * 24)) +#define PIOS_WS2811_MEMORYDATASIZE DMA_MemoryDataSize_HalfWord +#define PIOS_WS2811_PERIPHERALDATASIZE DMA_PeripheralDataSize_HalfWord +#define PIOS_WS2811_TIM_PERIOD 20 + +// Following times are keept on the lower side to accounts +// for bus contentions and irq response time +#define PIOS_WS2811_T0_HIGH_PERIOD 25 // .35us +/- 150nS +#define PIOS_WS2811_T1_HIGH_PERIOD 60 // .70us +/- 150nS + +#define PIOS_WS2811_DMA_CH1_CONFIG(channel) \ + { \ + .DMA_BufferSize = PIOS_WS2811_BUFFER_SIZE, \ + .DMA_Channel = channel, \ + .DMA_DIR = DMA_DIR_MemoryToPeripheral, \ + .DMA_FIFOMode = DMA_FIFOMode_Enable, \ + .DMA_FIFOThreshold = DMA_FIFOThreshold_HalfFull, \ + .DMA_Memory0BaseAddr = 0, \ + .DMA_MemoryBurst = DMA_MemoryBurst_INC4, \ + .DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \ + .DMA_MemoryInc = DMA_MemoryInc_Enable, \ + .DMA_Mode = DMA_Mode_Circular, \ + .DMA_PeripheralBaseAddr = 0, \ + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \ + .DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \ + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, \ + .DMA_Priority = DMA_Priority_VeryHigh, } + +#define PIOS_WS2811_DMA_CH2_CONFIG(channel) \ + { \ + .DMA_BufferSize = 4, \ + .DMA_Channel = channel, \ + .DMA_DIR = DMA_DIR_MemoryToPeripheral, \ + .DMA_FIFOMode = DMA_FIFOMode_Enable, \ + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, \ + .DMA_Memory0BaseAddr = 0, \ + .DMA_MemoryBurst = DMA_MemoryBurst_INC4, \ + .DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \ + .DMA_MemoryInc = DMA_MemoryInc_Enable, \ + .DMA_Mode = DMA_Mode_Circular, \ + .DMA_PeripheralBaseAddr = 0, \ + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \ + .DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \ + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, \ + .DMA_Priority = DMA_Priority_VeryHigh, } + +#define PIOS_WS2811_DMA_UPDATE_CONFIG(channel) \ + { \ + .DMA_BufferSize = 4, \ + .DMA_Channel = channel, \ + .DMA_DIR = DMA_DIR_MemoryToPeripheral, \ + .DMA_FIFOMode = DMA_FIFOMode_Enable, \ + .DMA_FIFOThreshold = DMA_FIFOThreshold_Full, \ + .DMA_Memory0BaseAddr = 0, \ + .DMA_MemoryBurst = DMA_MemoryBurst_INC4, \ + .DMA_MemoryDataSize = PIOS_WS2811_MEMORYDATASIZE, \ + .DMA_MemoryInc = DMA_MemoryInc_Enable, \ + .DMA_Mode = DMA_Mode_Circular, \ + .DMA_PeripheralBaseAddr = 0, \ + .DMA_PeripheralBurst = DMA_PeripheralBurst_Single, \ + .DMA_PeripheralDataSize = PIOS_WS2811_PERIPHERALDATASIZE, \ + .DMA_PeripheralInc = DMA_PeripheralInc_Disable, \ + .DMA_Priority = DMA_Priority_High } + + +typedef uint16_t ledbuf_t; + +struct pios_ws2811_pin_cfg { + GPIO_TypeDef *gpio; + GPIO_InitTypeDef gpioInit; +}; +struct pios_ws2811_cfg { + TIM_TimeBaseInitTypeDef timerInit; + TIM_TypeDef *timer; + uint8_t timerCh1; + uint8_t timerCh2; + + DMA_InitTypeDef dmaInitCh1; + DMA_Stream_TypeDef *streamCh1; + uint32_t dmaItCh1; + + DMA_InitTypeDef dmaInitCh2; + DMA_Stream_TypeDef *streamCh2; + uint32_t dmaItCh2; + + DMA_InitTypeDef dmaInitUpdate; + DMA_Stream_TypeDef *streamUpdate; + uint32_t dmaItUpdate; + uint16_t dmaSource; + struct stm32_irq irq; +}; + +void PIOS_WS2811_Init(const struct pios_ws2811_cfg *ws2811_cfg, const struct pios_ws2811_pin_cfg *ws2811_pin_cfg); + +void PIOS_WS2811_DMA_irq_handler(); +#endif /* PIOS_WS2811_H_ */ diff --git a/flight/pios/stm32f4xx/pios_ws2811.c b/flight/pios/stm32f4xx/pios_ws2811.c index f4ffe1bed..7762cdfb5 100644 --- a/flight/pios/stm32f4xx/pios_ws2811.c +++ b/flight/pios/stm32f4xx/pios_ws2811.c @@ -29,7 +29,7 @@ #ifdef PIOS_INCLUDE_WS2811 -#include "pios_ws2811.h" +#include "pios_ws2811_cfg.h" #include #include #include "FreeRTOS.h" diff --git a/flight/targets/boards/discoveryf4bare/board_hw_defs.c b/flight/targets/boards/discoveryf4bare/board_hw_defs.c index 4583fe6b4..097a8e193 100644 --- a/flight/targets/boards/discoveryf4bare/board_hw_defs.c +++ b/flight/targets/boards/discoveryf4bare/board_hw_defs.c @@ -1811,7 +1811,7 @@ const struct pios_usb_hid_cfg pios_usb_hid_cfg = { }; #endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */ #ifdef PIOS_INCLUDE_WS2811 -#include +#include #define PIOS_WS2811_TIM_DIVIDER (PIOS_PERIPHERAL_APB2_CLOCK / (800000 * PIOS_WS2811_TIM_PERIOD)) void DMA2_Stream1_IRQHandler(void) __attribute__((alias("PIOS_WS2811_irq_handler"))); diff --git a/flight/targets/boards/revolution/board_hw_defs.c b/flight/targets/boards/revolution/board_hw_defs.c index 98fce19c7..3a7cf115f 100644 --- a/flight/targets/boards/revolution/board_hw_defs.c +++ b/flight/targets/boards/revolution/board_hw_defs.c @@ -1964,7 +1964,7 @@ const struct pios_usb_hid_cfg pios_usb_hid_cfg = { #endif /* PIOS_INCLUDE_USB_HID && PIOS_INCLUDE_USB_CDC */ #ifdef PIOS_INCLUDE_WS2811 -#include +#include #include #define PIOS_WS2811_TIM_DIVIDER (PIOS_PERIPHERAL_APB2_CLOCK / (800000 * PIOS_WS2811_TIM_PERIOD)) From f556a5e335cb3bdb47b183468536e5012a980993 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Wed, 13 Aug 2014 15:14:55 +0200 Subject: [PATCH 035/203] OP-1379 - Split simple notification and external lednotifications libraries --- flight/libraries/inc/lednotification.h | 33 +++ flight/libraries/inc/notification.h | 1 - flight/libraries/lednotification.c | 268 ++++++++++++++++++ flight/libraries/notification.c | 244 +--------------- flight/modules/System/systemmod.c | 10 +- .../boards/discoveryf4bare/firmware/Makefile | 1 + .../boards/revolution/firmware/Makefile | 1 + 7 files changed, 314 insertions(+), 244 deletions(-) create mode 100644 flight/libraries/inc/lednotification.h create mode 100644 flight/libraries/lednotification.c diff --git a/flight/libraries/inc/lednotification.h b/flight/libraries/inc/lednotification.h new file mode 100644 index 000000000..fadd100f0 --- /dev/null +++ b/flight/libraries/inc/lednotification.h @@ -0,0 +1,33 @@ +/** + ****************************************************************************** + * + * @file lednotification.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. + * @brief led notification library + * -- + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * 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 LEDNOTIFICATION_H_ +#define LEDNOTIFICATION_H_ +#include + +void LedNotificationExtLedsRun(); + + +#endif /* LEDNOTIFICATION_H_ */ diff --git a/flight/libraries/inc/notification.h b/flight/libraries/inc/notification.h index bcf85015c..2053a9609 100644 --- a/flight/libraries/inc/notification.h +++ b/flight/libraries/inc/notification.h @@ -25,7 +25,6 @@ */ #ifndef NOTIFICATION_H #define NOTIFICATION_H -#include // period of each blink phase #define LED_BLINK_PERIOD_MS 200 diff --git a/flight/libraries/lednotification.c b/flight/libraries/lednotification.c new file mode 100644 index 000000000..b2ca13597 --- /dev/null +++ b/flight/libraries/lednotification.c @@ -0,0 +1,268 @@ +/** + ****************************************************************************** + * + * @file lednotification.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. + * @brief led notification library. + * -- + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * 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 "inc/lednotification.h" +#include +#include +#include +#include +#include +#include +#include + +// Private defines + +// Maximum number of notifications enqueued when a higher priority notification is added +#define MAX_BACKGROUND_NOTIFICATIONS 5 +#define MAX_HANDLED_LED 1 + +#define BACKGROUND_SEQUENCE -1 +#define RESET_STEP -1 +#define GET_CURRENT_MILLIS (xTaskGetTickCount() * portTICK_RATE_MS) + +// Private data types definition +// this is the status for a single notification led set +typedef struct { + int8_t queued_priorities[MAX_BACKGROUND_NOTIFICATIONS]; + LedSequence_t queued_sequences[MAX_BACKGROUND_NOTIFICATIONS]; + LedSequence_t background_sequence; + uint32_t next_run_time; + uint32_t sequence_starting_time; + + int8_t active_sequence_num; // active queued sequence or BACKGROUND_SEQUENCE + bool running; // is this led running? + bool step_phase_on; // true = step on phase, false = step off phase + uint8_t next_sequence_step; // (step number to be executed) << 1 || (0x00 = on phase, 0x01 = off phase) + uint8_t next_step_rep; // next repetition number for next step (valid if step.repeats >1) + uint8_t next_sequence_rep; // next sequence repetition counter (valid if sequence.repeats > 1) + uint8_t led_set; // target led set +} NotifierLedStatus_t; + +static bool led_status_initialized = false; + +NotifierLedStatus_t led_status[MAX_HANDLED_LED]; + +static void InitExtLed() +{ + memset(led_status, 0, sizeof(NotifierLedStatus_t) * MAX_HANDLED_LED); + const uint32_t now = GET_CURRENT_MILLIS; + for (uint8_t l = 0; l < MAX_HANDLED_LED; l++) { + led_status[l].led_set = 0; + led_status[l].next_run_time = now + 500; // start within half a second + for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { + led_status[l].queued_priorities[i] = NOTIFY_PRIORITY_BACKGROUND; + } + } +} + +/** + * restart current sequence + */ +static void restart_sequence(NotifierLedStatus_t *status, bool immediate) +{ + status->next_sequence_step = 0; + status->next_step_rep = 0; + status->step_phase_on = true; + status->running = true; + if (immediate) { + uint32_t currentTime = GET_CURRENT_MILLIS; + status->next_run_time = currentTime; + } + status->sequence_starting_time = status->next_run_time; +} + +/** + * modify background sequence or enqueue a new sequence to play + */ +static void push_queued_sequence(ExtLedNotification_t *new_notification, NotifierLedStatus_t *status) +{ + int8_t updated_sequence = BACKGROUND_SEQUENCE; + + if (new_notification->priority == NOTIFY_PRIORITY_BACKGROUND) { + status->background_sequence = new_notification->sequence; + } else { + // a notification with priority higher than background. + // try to enqueue it + int8_t insert_point = -1; + int8_t first_free = -1; + for (int8_t i = MAX_BACKGROUND_NOTIFICATIONS; i > -1; i--) { + const int8_t priority_i = status->queued_priorities[i]; + if (priority_i == NOTIFY_PRIORITY_BACKGROUND) { + first_free = i; + insert_point = i; + continue; + } + if (priority_i > new_notification->priority) { + insert_point = i; + } + } + + if (insert_point != first_free) { + // there is a free slot, move everything up one place + if (first_free != -1) { + for (uint8_t i = MAX_BACKGROUND_NOTIFICATIONS - 1; i > insert_point; i--) { + status->queued_priorities[i] = status->queued_priorities[i - 1]; + status->queued_sequences[i] = status->queued_sequences[i - 1]; + } + if (status->active_sequence_num >= insert_point) { + status->active_sequence_num++; + } + } else { + // no free space, discard lowest priority notification and move everything down + for (uint8_t i = 0; i < insert_point; i++) { + status->queued_priorities[i] = status->queued_priorities[i + 1]; + status->queued_sequences[i] = status->queued_sequences[i + 1]; + } + if (status->active_sequence_num <= insert_point) { + status->active_sequence_num--; + } + } + } + + status->queued_priorities[insert_point] = new_notification->priority; + status->queued_sequences[insert_point] = new_notification->sequence; + updated_sequence = insert_point; + } + + if (status->active_sequence_num < updated_sequence) { + status->active_sequence_num = updated_sequence; + restart_sequence(status, true); + } + if (updated_sequence == BACKGROUND_SEQUENCE) { + restart_sequence(status, false); + } +} + +static bool pop_queued_sequence(NotifierLedStatus_t *status) +{ + if (status->active_sequence_num != BACKGROUND_SEQUENCE) { + // start the lower priority item + status->queued_priorities[status->active_sequence_num] = NOTIFY_PRIORITY_BACKGROUND; + status->active_sequence_num--; + return true; + } + // background sequence was completed + return false; +} + +/** + * advance current sequence pointers for next step + */ +static void advance_sequence(NotifierLedStatus_t *status) +{ + LedSequence_t *activeSequence = + status->active_sequence_num == BACKGROUND_SEQUENCE ? + &status->background_sequence : &status->queued_sequences[status->active_sequence_num]; + + uint8_t step = status->next_sequence_step; + LedStep_t *currentStep = &activeSequence->steps[step]; + + // Next step will be the OFF phase, so just update the time and + if (status->step_phase_on) { + // next will be the off phase + status->next_run_time += currentStep->time_on; + status->step_phase_on = false; + // check if off phase should be skipped + if (currentStep->time_off != 0) { + return; + } + } + + // next step is ON phase. check whether to repeat current step or move to next one + status->next_run_time += currentStep->time_off; + status->step_phase_on = true; + + if (status->next_step_rep + 1 < currentStep->repeats) { + // setup next repetition + status->next_step_rep++; + return; + } + + // move to next step + LedStep_t *nextStep = (step + 1 < NOTIFY_SEQUENCE_MAX_STEPS) ? &activeSequence->steps[step + 1] : 0; + + // next step is null, check whether sequence must be repeated or it must move to lower priority queued or background sequences + if (NOTIFY_IS_NULL_STEP(nextStep)) { + if (activeSequence->repeats == -1 || status->next_sequence_rep + 1 < activeSequence->repeats) { + status->next_sequence_rep++; + // restart the sequence + restart_sequence(status, false); + return; + } + if (status->active_sequence_num != BACKGROUND_SEQUENCE) { + // no repeat, pop enqueued or background sequences + pop_queued_sequence(status); + restart_sequence(status, false); + status->next_sequence_rep = 0; + } else { + status->running = false; + } + } else { + status->next_step_rep = 0; + status->next_sequence_step++; + } +} + +/** + * run a led set + */ +static void run_led(NotifierLedStatus_t *status) +{ + uint32_t currentTime = GET_CURRENT_MILLIS; + + if (!status->running || currentTime < status->next_run_time) { + return; + } + status->next_run_time = currentTime; + uint8_t step = status->next_sequence_step; + + LedSequence_t *activeSequence = status->active_sequence_num == BACKGROUND_SEQUENCE ? + &status->background_sequence : &status->queued_sequences[status->active_sequence_num]; + if (status->step_phase_on) { + PIOS_WS2811_setColorRGB(activeSequence->steps[step].color, status->led_set, true); + } else { + PIOS_WS2811_setColorRGB(Color_Off, status->led_set, true); + } + advance_sequence(status); +} + +void LedNotificationExtLedsRun() +{ + // handle incoming sequences + if (!led_status_initialized) { + InitExtLed(); + led_status_initialized = true; + } + static ExtLedNotification_t *newNotification; + newNotification = PIOS_NOTIFY_GetNewExtLedSequence(true); + if (newNotification) { + push_queued_sequence(newNotification, &led_status[0]); + } + + // Run Leds + for (uint8_t i = 0; i < MAX_HANDLED_LED; i++) { + run_led(&led_status[i]); + } +} diff --git a/flight/libraries/notification.c b/flight/libraries/notification.c index c02152e02..cf704d4d5 100644 --- a/flight/libraries/notification.c +++ b/flight/libraries/notification.c @@ -31,40 +31,10 @@ #include #include -#ifdef PIOS_INCLUDE_WS2811 -#include -#endif -// Private defines -// Maximum number of notifications enqueued when a higher priority notification is added -#define MAX_BACKGROUND_NOTIFICATIONS 3 -#define MAX_HANDLED_LED 1 -#define BACKGROUND_SEQUENCE -1 -#define RESET_STEP -1 -#define GET_CURRENT_MILLIS (xTaskGetTickCount() * portTICK_RATE_MS) +#define GET_CURRENT_MILLIS (xTaskGetTickCount() * portTICK_RATE_MS) // Private data types definition -// this is the status for a single LED notification led set -typedef struct { - int8_t queued_priorities[MAX_BACKGROUND_NOTIFICATIONS]; - LedSequence_t queued_sequences[MAX_BACKGROUND_NOTIFICATIONS]; - LedSequence_t background_sequence; - uint32_t next_run_time; - uint32_t sequence_starting_time; - - int8_t active_sequence_num; // active queued sequence or BACKGROUND_SEQUENCE - bool running; // is this led running? - bool step_phase_on; // true = step on phase, false = step off phase - uint8_t next_sequence_step; // (step number to be executed) << 1 || (0x00 = on phase, 0x01 = off phase) - uint8_t next_step_rep; // next repetition number for next step (valid if step.repeats >1) - uint8_t next_sequence_rep; // next sequence repetition counter (valid if sequence.repeats > 1) - uint8_t led_set; // target led set -} NotifierLedStatus_t; - -#ifdef PIOS_INCLUDE_WS2811 -static bool led_status_initialized = false; -#endif - #ifdef PIOS_LED_ALARM #define ALARM_LED_ON() PIOS_LED_On(PIOS_LED_ALARM) #define ALARM_LED_OFF() PIOS_LED_Off(PIOS_LED_ALARM) @@ -173,7 +143,6 @@ static bool handleNotifications(pios_notify_notification runningNotification, ui static void handleFlightMode(uint16_t *r_pattern, uint16_t *b_pattern); static void handleHeartbeat(uint16_t *r_pattern, uint16_t *b_pattern); -static void HandleExtLeds(); void NotificationUpdateStatus() { @@ -202,8 +171,8 @@ void NotificationOnboardLedsRun() STATUS_LENGHT } status; - HandleExtLeds(); const uint32_t current_timestamp = GET_CURRENT_MILLIS; + if (!started || (current_timestamp - lastRunTimestamp) < LED_BLINK_PERIOD_MS) { return; } @@ -334,212 +303,3 @@ static void handleHeartbeat(uint16_t *r_pattern, uint16_t *b_pattern) *b_pattern = BLINK_B_HEARTBEAT_PATTERN; *r_pattern = BLINK_R_HEARTBEAT_PATTERN; } - -#ifdef PIOS_INCLUDE_WS2811 - -NotifierLedStatus_t led_status[MAX_HANDLED_LED]; - -static void InitExtLed() -{ - memset(led_status, 0, sizeof(NotifierLedStatus_t) * MAX_HANDLED_LED); - const uint32_t now = GET_CURRENT_MILLIS; - for (uint8_t l = 0; l < MAX_HANDLED_LED; l++) { - led_status[l].led_set = l; - led_status[l].next_run_time = now + 500; // start within half a second - for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { - led_status[l].queued_priorities[i] = NOTIFY_PRIORITY_BACKGROUND; - } - } -} - -/** - * restart current sequence - */ -static void restart_sequence(NotifierLedStatus_t *status, bool immediate) -{ - status->next_sequence_step = 0; - status->next_step_rep = 0; - status->step_phase_on = true; - status->running = true; - if (immediate) { - uint32_t currentTime = GET_CURRENT_MILLIS; - status->next_run_time = currentTime; - } - status->sequence_starting_time = status->next_run_time; -} - -/** - * modify background sequence or enqueue a new sequence to play - */ -static void push_queued_sequence(ExtLedNotification_t *new_notification, NotifierLedStatus_t *status) -{ - int8_t updated_sequence = BACKGROUND_SEQUENCE; - - if (new_notification->priority == NOTIFY_PRIORITY_BACKGROUND) { - status->background_sequence = new_notification->sequence; - } else { - // a notification with priority higher than background. - // try to enqueue it - int8_t insert_point = -1; - int8_t first_free = -1; - for (int8_t i = MAX_BACKGROUND_NOTIFICATIONS; i > -1; i--) { - const int8_t priority_i = status->queued_priorities[i]; - if (priority_i == NOTIFY_PRIORITY_BACKGROUND) { - first_free = i; - insert_point = i; - continue; - } - if (priority_i > new_notification->priority) { - insert_point = i; - } - } - - if (insert_point != first_free) { - // there is a free slot, move everything up one place - if (first_free != -1) { - for (uint8_t i = MAX_BACKGROUND_NOTIFICATIONS - 1; i > insert_point; i--) { - status->queued_priorities[i] = status->queued_priorities[i - 1]; - status->queued_sequences[i] = status->queued_sequences[i - 1]; - } - if (status->active_sequence_num >= insert_point) { - status->active_sequence_num++; - } - } else { - // no free space, discard lowest priority notification and move everything down - for (uint8_t i = 0; i < insert_point; i++) { - status->queued_priorities[i] = status->queued_priorities[i + 1]; - status->queued_sequences[i] = status->queued_sequences[i + 1]; - } - if (status->active_sequence_num <= insert_point) { - status->active_sequence_num--; - } - } - } - - status->queued_priorities[insert_point] = new_notification->priority; - status->queued_sequences[insert_point] = new_notification->sequence; - updated_sequence = insert_point; - } - - if (status->active_sequence_num < updated_sequence) { - status->active_sequence_num = updated_sequence; - restart_sequence(status, true); - } - if (updated_sequence == BACKGROUND_SEQUENCE) { - restart_sequence(status, false); - } -} - -static bool pop_queued_sequence(NotifierLedStatus_t *status) -{ - if (status->active_sequence_num != BACKGROUND_SEQUENCE) { - // start the lower priority item - status->queued_priorities[status->active_sequence_num] = NOTIFY_PRIORITY_BACKGROUND; - status->active_sequence_num--; - return true; - } - // background sequence was completed - return false; -} - -/** - * advance current sequence pointers for next step - */ -static void advance_sequence(NotifierLedStatus_t *status) -{ - LedSequence_t *activeSequence = - status->active_sequence_num == BACKGROUND_SEQUENCE ? - &status->background_sequence : &status->queued_sequences[status->active_sequence_num]; - - uint8_t step = status->next_sequence_step; - LedStep_t *currentStep = &activeSequence->steps[step]; - - // Next step will be the OFF phase, so just update the time and - if (status->step_phase_on) { - // next will be the off phase - status->next_run_time += currentStep->time_on; - status->step_phase_on = false; - // check if off phase should be skipped - if (currentStep->time_off != 0) { - return; - } - } - - // next step is ON phase. check whether to repeat current step or move to next one - status->next_run_time += currentStep->time_off; - status->step_phase_on = true; - - if (status->next_step_rep + 1 < currentStep->repeats) { - // setup next repetition - status->next_step_rep++; - return; - } - - // move to next step - LedStep_t *nextStep = (step + 1 < NOTIFY_SEQUENCE_MAX_STEPS) ? &activeSequence->steps[step + 1] : 0; - - // next step is null, check whether sequence must be repeated or it must move to lower priority queued or background sequences - if (NOTIFY_IS_NULL_STEP(nextStep)) { - if (activeSequence->repeats == -1 || status->next_sequence_rep + 1 < activeSequence->repeats) { - status->next_sequence_rep++; - // restart the sequence - restart_sequence(status, false); - return; - } - if (status->active_sequence_num != BACKGROUND_SEQUENCE) { - // no repeat, pop enqueued or background sequences - pop_queued_sequence(status); - restart_sequence(status, false); - } else { - status->running = false; - } - } else { - status->next_step_rep = 0; - status->next_sequence_step++; - } -} - -/** - * run a led set - */ -static void run_led(NotifierLedStatus_t *status) -{ - uint32_t currentTime = GET_CURRENT_MILLIS; - - if (!status->running || currentTime < status->next_run_time) { - return; - } - status->next_run_time = currentTime; - uint8_t step = status->next_sequence_step; - - LedSequence_t *activeSequence = status->active_sequence_num == BACKGROUND_SEQUENCE ? - &status->background_sequence : &status->queued_sequences[status->active_sequence_num]; - if (status->step_phase_on) { - PIOS_WS2811_setColorRGB(activeSequence->steps[step].color, status->led_set, true); - } else { - PIOS_WS2811_setColorRGB(Color_Off, status->led_set, true); - } - advance_sequence(status); -} - -void HandleExtLeds() -{ - // handle incoming sequences - if (!led_status_initialized) { - InitExtLed(); - led_status_initialized = true; - } - static ExtLedNotification_t *newNotification; - newNotification = PIOS_NOTIFY_GetNewExtLedSequence(true); - if (newNotification) { - push_queued_sequence(newNotification, &led_status[0]); - } - - // Run Leds - for (uint8_t i = 0; i < MAX_HANDLED_LED; i++) { - run_led(&led_status[i]); - } -} -#else /* ifdef PIOS_INCLUDE_WS2811 */ -void HandleExtLeds() {} -#endif /* ifdef PIOS_INCLUDE_WS2811 */ diff --git a/flight/modules/System/systemmod.c b/flight/modules/System/systemmod.c index aa6a8f54d..e37168061 100644 --- a/flight/modules/System/systemmod.c +++ b/flight/modules/System/systemmod.c @@ -42,7 +42,11 @@ #include // private includes #include "inc/systemmod.h" -#include "notification.h" + +#include +#ifdef PIOS_INCLUDE_WS2811 +#include +#endif // UAVOs #include @@ -55,6 +59,7 @@ #include #include #include +#include #ifdef PIOS_INCLUDE_INSTRUMENTATION #include @@ -633,6 +638,9 @@ static void updateSystemAlarms() void vApplicationIdleHook(void) { NotificationOnboardLedsRun(); +#ifdef PIOS_INCLUDE_WS2811 + LedNotificationExtLedsRun(); +#endif } /** * Called by the RTOS when a stack overflow is detected. diff --git a/flight/targets/boards/discoveryf4bare/firmware/Makefile b/flight/targets/boards/discoveryf4bare/firmware/Makefile index 608d2b6cf..29cf57378 100644 --- a/flight/targets/boards/discoveryf4bare/firmware/Makefile +++ b/flight/targets/boards/discoveryf4bare/firmware/Makefile @@ -87,6 +87,7 @@ ifndef TESTAPP SRC += $(FLIGHTLIB)/plans.c SRC += $(FLIGHTLIB)/WorldMagModel.c SRC += $(FLIGHTLIB)/insgps13state.c + SRC += $(FLIGHTLIB)/lednotification.c ## UAVObjects include ./UAVObjects.inc diff --git a/flight/targets/boards/revolution/firmware/Makefile b/flight/targets/boards/revolution/firmware/Makefile index cb99372f1..e4220ade0 100644 --- a/flight/targets/boards/revolution/firmware/Makefile +++ b/flight/targets/boards/revolution/firmware/Makefile @@ -88,6 +88,7 @@ ifndef TESTAPP SRC += $(FLIGHTLIB)/plans.c SRC += $(FLIGHTLIB)/WorldMagModel.c SRC += $(FLIGHTLIB)/insgps13state.c + SRC += $(FLIGHTLIB)/lednotification.c ## UAVObjects include ./UAVObjects.inc From 376aa0052f212412b5ad2c83e24c97868767fa00 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Wed, 13 Aug 2014 15:18:17 +0200 Subject: [PATCH 036/203] OP-1379 - Initial Notify module. Supports: 1) predefined seqences associated with each flightmode. 2) fixed table with alarm index and assciated led warn/error sequences/repetition rate. --- flight/modules/Notify/inc/notify.h | 33 ++ flight/modules/Notify/inc/sequences.h | 417 ++++++++++++++++++ flight/modules/Notify/notify.c | 142 ++++++ .../boards/revolution/firmware/Makefile | 1 + 4 files changed, 593 insertions(+) create mode 100644 flight/modules/Notify/inc/notify.h create mode 100644 flight/modules/Notify/inc/sequences.h create mode 100644 flight/modules/Notify/notify.c diff --git a/flight/modules/Notify/inc/notify.h b/flight/modules/Notify/inc/notify.h new file mode 100644 index 000000000..1b779bf27 --- /dev/null +++ b/flight/modules/Notify/inc/notify.h @@ -0,0 +1,33 @@ +/** + ****************************************************************************** + * + * @file notify.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Notify module, show events and status on external led. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * 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 NOTIFY_H_ +#define NOTIFY_H_ + + +int32_t NotifyInitialize(void); + + +#endif /* NOTIFY_H_ */ diff --git a/flight/modules/Notify/inc/sequences.h b/flight/modules/Notify/inc/sequences.h new file mode 100644 index 000000000..ebb9bafb6 --- /dev/null +++ b/flight/modules/Notify/inc/sequences.h @@ -0,0 +1,417 @@ +/** + ****************************************************************************** + * + * @file sequences.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Notify module, sequences configuration. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * 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 SEQUENCES_H_ +#define SEQUENCES_H_ +#include +#include +#include +#include +#include + +typedef enum { + NOTIFY_SEQUENCE_ARMED_FM_MANUAL = 0, + NOTIFY_SEQUENCE_ARMED_FM_STABILIZED1 = 1, + NOTIFY_SEQUENCE_ARMED_FM_STABILIZED2 = 2, + NOTIFY_SEQUENCE_ARMED_FM_STABILIZED3 = 3, + NOTIFY_SEQUENCE_ARMED_FM_STABILIZED4 = 4, + NOTIFY_SEQUENCE_ARMED_FM_STABILIZED5 = 5, + NOTIFY_SEQUENCE_ARMED_FM_STABILIZED6 = 6, + NOTIFY_SEQUENCE_ARMED_FM_AUTOTUNE = 7, + NOTIFY_SEQUENCE_ARMED_FM_GPS = 8, + NOTIFY_SEQUENCE_ARMED_FM_RTH = 9, + NOTIFY_SEQUENCE_ARMED_FM_LAND = 10, + NOTIFY_SEQUENCE_ARMED_FM_AUTO = 11, + NOTIFY_SEQUENCE_ALM_WARN_GPS = 12, + NOTIFY_SEQUENCE_ALM_ERROR_GPS = 13, + NOTIFY_SEQUENCE_ALM_WARN_BATTERY = 14, + NOTIFY_SEQUENCE_ALM_ERROR_BATTERY = 15, + NOTIFY_SEQUENCE_ALM_MAG = 16, + NOTIFY_SEQUENCE_ALM_CONFIG = 17, + NOTIFY_SEQUENCE_DISARMED = 18, +} NotifySequences; + +typedef struct { + uint32_t timeBetweenNotifications; + uint8_t alarmIndex; + uint8_t warnNotification; + uint8_t errorNotification; +} AlarmDefinition_t; + +// consts +const LedSequence_t notifications[] = { + [NOTIFY_SEQUENCE_DISARMED] = { + .repeats = -1, + .steps = { + { + .time_off = 1000, + .time_on = 1000, + .color = COLOR_BLUE, + .repeats = 1, + }, + { + .time_off = 1000, + .time_on = 1000, + .color = COLOR_LIME, + .repeats = 1, + }, + { + .time_off = 1000, + .time_on = 1000, + .color = COLOR_RED, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ARMED_FM_MANUAL] = { + .repeats = -1, + .steps = { + { + .time_off = 900, + .time_on = 100, + .color = COLOR_YELLOW, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED1] = { + .repeats = -1, + .steps = { + { + .time_off = 900, + .time_on = 100, + .color = COLOR_BLUE, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED2] = { + .repeats = -1, + .steps = { + { + .time_off = 100, + .time_on = 100, + .color = COLOR_BLUE, + .repeats = 1, + }, + { + .time_off = 700, + .time_on = 100, + .color = COLOR_BLUE, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED3] = { + .repeats = -1, + .steps = { + { + .time_off = 100, + .time_on = 100, + .color = COLOR_BLUE, + .repeats = 2, + }, + { + .time_off = 500, + .time_on = 100, + .color = COLOR_BLUE, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED4] = { + .repeats = -1, + .steps = { + { + .time_off = 900, + .time_on = 100, + .color = COLOR_PURPLE, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED5] = { + .repeats = -1, + .steps = { + { + .time_off = 100, + .time_on = 100, + .color = COLOR_PURPLE, + .repeats = 1, + }, + { + .time_off = 700, + .time_on = 100, + .color = COLOR_BLUE, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED6] = { + .repeats = -1, + .steps = { + { + .time_off = 100, + .time_on = 100, + .color = COLOR_PURPLE, + .repeats = 1, + }, + { + .time_off = 100, + .time_on = 100, + .color = COLOR_PURPLE, + .repeats = 1, + }, + { + .time_off = 500, + .time_on = 100, + .color = COLOR_BLUE, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ARMED_FM_AUTOTUNE] = { + .repeats = -1, + .steps = { + { + .time_off = 800, + .time_on = 200, + .color = COLOR_BLUE, + .repeats = 1, + }, + }, + }, + + [NOTIFY_SEQUENCE_ARMED_FM_GPS] = { + .repeats = -1, + .steps = { + { + .time_off = 800, + .time_on = 200, + .color = COLOR_GREEN, + .repeats = 1, + }, + }, + }, + + [NOTIFY_SEQUENCE_ARMED_FM_RTH] = { + .repeats = -1, + .steps = { + { + .time_off = 100, + .time_on = 200, + .color = COLOR_GREEN, + .repeats = 1, + }, + { + .time_off = 500, + .time_on = 200, + .color = COLOR_GREEN, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ARMED_FM_LAND] = { + .repeats = -1, + .steps = { + { + .time_off = 100, + .time_on = 200, + .color = COLOR_GREEN, + .repeats = 1, + }, + { + .time_off = 100, + .time_on = 200, + .color = COLOR_BLUE, + .repeats = 1, + }, + { + .time_off = 100, + .time_on = 200, + .color = COLOR_GREEN, + .repeats = 1, + }, + { + .time_off = 100, + .time_on = 200, + .color = COLOR_BLUE, + .repeats = 1, + }, + { + .time_off = 100, + .time_on = 200, + .color = COLOR_GREEN, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ARMED_FM_AUTO] = { + .repeats = -1, + .steps = { + { + .time_off = 100, + .time_on = 200, + .color = COLOR_GREEN, + .repeats = 2, + }, + { + .time_off = 500, + .time_on = 200, + .color = COLOR_GREEN, + .repeats = 1, + }, + }, + }, + + [NOTIFY_SEQUENCE_ALM_WARN_GPS] = { + .repeats = 2, + .steps = { + { + .time_off = 300, + .time_on = 300, + .color = COLOR_ORANGE, + .repeats = 2, + }, + { + .time_off = 300, + .time_on = 300, + .color = COLOR_YELLOW, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ALM_ERROR_GPS] = { + .repeats = 2, + .steps = { + { + .time_off = 300, + .time_on = 300, + .color = COLOR_RED, + .repeats = 2, + }, + { + .time_off = 300, + .time_on = 300, + .color = COLOR_YELLOW, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ALM_WARN_BATTERY] = { + .repeats = 1, + .steps = { + { + .time_off = 100, + .time_on = 100, + .color = COLOR_ORANGE, + .repeats = 10, + }, + }, + }, + [NOTIFY_SEQUENCE_ALM_ERROR_BATTERY] = { + .repeats = 1, + .steps = { + { + .time_off = 100, + .time_on = 100, + .color = COLOR_RED, + .repeats = 10, + }, + }, + }, + [NOTIFY_SEQUENCE_ALM_MAG] = { + .repeats = 1, + .steps = { + { + .time_off = 300, + .time_on = 300, + .color = COLOR_RED, + .repeats = 2, + }, + { + .time_off = 300, + .time_on = 300, + .color = COLOR_GREEN, + .repeats = 1, + }, + }, + }, + [NOTIFY_SEQUENCE_ALM_CONFIG] = { + .repeats = -1, + .steps = { + { + .time_off = 500, + .time_on = 100, + .color = COLOR_RED, + .repeats = 1, + }, + }, + }, +}; + +const LedSequence_t *flightModeMap[] = { + [FLIGHTSTATUS_FLIGHTMODE_MANUAL] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_MANUAL], + [FLIGHTSTATUS_FLIGHTMODE_STABILIZED1] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED1], + [FLIGHTSTATUS_FLIGHTMODE_STABILIZED2] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED2], + [FLIGHTSTATUS_FLIGHTMODE_STABILIZED3] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED3], + [FLIGHTSTATUS_FLIGHTMODE_STABILIZED4] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED4], + [FLIGHTSTATUS_FLIGHTMODE_STABILIZED5] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED5], + [FLIGHTSTATUS_FLIGHTMODE_STABILIZED6] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED6], + [FLIGHTSTATUS_FLIGHTMODE_PATHPLANNER] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_AUTO], + [FLIGHTSTATUS_FLIGHTMODE_AUTOTUNE] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_AUTOTUNE], + [FLIGHTSTATUS_FLIGHTMODE_POSITIONHOLD] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS], + [FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIOFPV] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS], + [FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIOLOS] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS], + [FLIGHTSTATUS_FLIGHTMODE_POSITIONVARIONSEW] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS], + [FLIGHTSTATUS_FLIGHTMODE_RETURNTOBASE] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_RTH], + [FLIGHTSTATUS_FLIGHTMODE_LAND] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_LAND], + [FLIGHTSTATUS_FLIGHTMODE_POI] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS], + [FLIGHTSTATUS_FLIGHTMODE_AUTOCRUISE] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS], +}; + +const AlarmDefinition_t alarmsMap[] = { + { + .timeBetweenNotifications = 10000, + .alarmIndex = SYSTEMALARMS_ALARM_GPS, + .warnNotification = NOTIFY_SEQUENCE_ALM_WARN_GPS, + .errorNotification = NOTIFY_SEQUENCE_ALM_ERROR_GPS, + }, + { + .timeBetweenNotifications = 15000, + .alarmIndex = SYSTEMALARMS_ALARM_MAGNETOMETER, + .warnNotification = NOTIFY_SEQUENCE_ALM_MAG, + .errorNotification = NOTIFY_SEQUENCE_ALM_MAG, + }, + { + .timeBetweenNotifications = 15000, + .alarmIndex = SYSTEMALARMS_ALARM_BATTERY, + .warnNotification = NOTIFY_SEQUENCE_ALM_WARN_BATTERY, + .errorNotification = NOTIFY_SEQUENCE_ALM_ERROR_BATTERY, + }, +}; +const uint8_t alarmsMapSize = NELEMENTS(alarmsMap); + +#endif /* SEQUENCES_H_ */ diff --git a/flight/modules/Notify/notify.c b/flight/modules/Notify/notify.c new file mode 100644 index 000000000..a944690cb --- /dev/null +++ b/flight/modules/Notify/notify.c @@ -0,0 +1,142 @@ +/** + ****************************************************************************** + * + * @file notify.c + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2010. + * @brief Notify module, show events and status on external led. + * + * @see The GNU Public License (GPL) Version 3 + * + *****************************************************************************/ +/* + * 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 + */ + +/** + * Input objects: ExampleObject1, ExampleSettings + * Output object: ExampleObject2 + * + * This module executes in response to ExampleObject1 updates. When the + * module is triggered it will update the data of ExampleObject2. + * + * No threads are used in this example. + * + * UAVObjects are automatically generated by the UAVObjectGenerator from + * the object definition XML file. + * + * Modules have no API, all communication to other modules is done through UAVObjects. + * However modules may use the API exposed by shared libraries. + * See the OpenPilot wiki for more details. + * http://www.openpilot.org/OpenPilot_Application_Architecture + * + */ +#include "openpilot.h" +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "inc/notify.h" +#include "inc/sequences.h" +#include + +#define SAMPLE_PERIOD_MS 250 +// private types +typedef struct { + uint32_t lastAlarmTime; + uint8_t lastAlarm; +} AlarmStatus_t; +// function declarations +static void updatedCb(UAVObjEvent *ev); +static void onTimerCb(UAVObjEvent *ev); +static void checkAlarm(uint8_t alarm, uint8_t *last_alarm, uint32_t *last_alm_time, + uint8_t warn_sequence, uint8_t error_sequence, + uint32_t timeBetweenNotifications); +static AlarmStatus_t *alarmStatus; +int32_t NotifyInitialize(void) +{ + alarmStatus = (AlarmStatus_t *)pios_malloc(sizeof(AlarmStatus_t) * alarmsMapSize); + for (uint8_t i = 0; i < alarmsMapSize; i++) { + alarmStatus[i].lastAlarm = SYSTEMALARMS_ALARM_OK; + alarmStatus[i].lastAlarmTime = 0; + } + + FlightStatusConnectCallback(&updatedCb); + updatedCb(0); + static UAVObjEvent ev; + memset(&ev, 0, sizeof(UAVObjEvent)); + EventPeriodicCallbackCreate(&ev, onTimerCb, SAMPLE_PERIOD_MS / portTICK_RATE_MS); + return 0; +} +MODULE_INITCALL(NotifyInitialize, 0); + + +void updatedCb(UAVObjEvent *ev) +{ + if (!ev || ev->obj == FlightStatusHandle()) { + static uint8_t last_armed = 0xff; + static uint8_t last_flightmode = 0xff; + uint8_t armed; + uint8_t flightmode; + FlightStatusArmedGet(&armed); + FlightStatusFlightModeGet(&flightmode); + if (last_armed != armed || (armed && flightmode != last_flightmode)) { + if (armed) { + PIOS_NOTIFICATION_Default_Ext_Led_Play(flightModeMap[flightmode], NOTIFY_PRIORITY_BACKGROUND); + } else { + PIOS_NOTIFICATION_Default_Ext_Led_Play(¬ifications[NOTIFY_SEQUENCE_DISARMED], NOTIFY_PRIORITY_BACKGROUND); + } + } + last_armed = armed; + last_flightmode = flightmode; + } +} + +void onTimerCb(__attribute__((unused)) UAVObjEvent *ev) +{ + static SystemAlarmsAlarmData alarms; + + SystemAlarmsAlarmGet(&alarms); + for (uint8_t i = 0; i < alarmsMapSize; i++) { + uint8_t alarm = ((uint8_t *)&alarms)[alarmsMap[i].alarmIndex]; + checkAlarm(alarm, + &alarmStatus[i].lastAlarm, + &alarmStatus[i].lastAlarmTime, + alarmsMap[i].warnNotification, + alarmsMap[i].errorNotification, + alarmsMap[i].timeBetweenNotifications); + } +} + +void checkAlarm(uint8_t alarm, uint8_t *last_alarm, uint32_t *last_alm_time, uint8_t warn_sequence, uint8_t error_sequence, uint32_t timeBetweenNotifications) +{ + if (alarm > SYSTEMALARMS_ALARM_OK) { + uint32_t current_time = PIOS_DELAY_GetuS(); + if (*last_alarm < alarm || *last_alm_time + timeBetweenNotifications < current_time) { + uint8_t sequence = (alarm == SYSTEMALARMS_ALARM_WARNING) ? warn_sequence : error_sequence; + PIOS_NOTIFICATION_Default_Ext_Led_Play( + ¬ifications[sequence], + alarm == SYSTEMALARMS_ALARM_WARNING ? NOTIFY_PRIORITY_REGULAR : NOTIFY_PRIORITY_CRITICAL); + *last_alarm = alarm; + *last_alm_time = current_time; + } + } else { + *last_alarm = SYSTEMALARMS_ALARM_OK; + } +} diff --git a/flight/targets/boards/revolution/firmware/Makefile b/flight/targets/boards/revolution/firmware/Makefile index e4220ade0..b544ab4dd 100644 --- a/flight/targets/boards/revolution/firmware/Makefile +++ b/flight/targets/boards/revolution/firmware/Makefile @@ -50,6 +50,7 @@ MODULES += FixedWingPathFollower MODULES += Osd/osdoutout MODULES += Logging MODULES += Telemetry +MODULES += Notify OPTMODULES += ComUsbBridge From dd07ccbec9b235da531eb8964cb0f09b70dbcdeb Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sat, 16 Aug 2014 14:20:31 +1000 Subject: [PATCH 037/203] Resolve merge conflicts --- .../pages/outputcalibrationpage.cpp | 21 +++++++++---------- .../setupwizard/vehicleconfigurationsource.h | 8 +------ 2 files changed, 11 insertions(+), 18 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index f2f79c5f5..d724f6076 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -137,10 +137,16 @@ void OutputCalibrationPage::setupVehicle() m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6; m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; break; -<<<<<<< HEAD + case SetupWizard::MULTI_ROTOR_HEXA_X: + m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; + m_vehicleElementIds << "hexa-x" << "hexa-x-frame" << "hexa-x-m1" << "hexa-x-m2" << "hexa-x-m3" << "hexa-x-m4" << "hexa-x-m5" << "hexa-x-m6"; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6; + m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; + break; + // Fixed Wing case SetupWizard::FIXED_WING_AILERON: loadSVGFile(FIXEDWING_SVG_FILE); - m_wizardIndexes << 0 << 1 << 2 << 2 << 2 << 2; //2 for servoCenterSlider! + m_wizardIndexes << 0 << 1 << 2 << 2 << 2 << 2; //2 for servoCenterSlider! m_vehicleElementIds << "aileron" << "aileron-frame" << "aileron-motor" << "aileron-ail-left" << "aileron-ail-right" << "aileron-rudder" << "aileron-elevator"; m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5; m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4; @@ -148,7 +154,7 @@ void OutputCalibrationPage::setupVehicle() // see Servo city for an example. 1500 usec is center on MS85mg for example. // - http://www.servocity.com/html/hs-85mg__mighty_micro.html // make sure Aileron servo one does not go to an extreme value - // would also be nice to make these all default to 50hz so we don't shred servos. + // would also be nice to make these all default to 50hz so we don't shred servos. m_actuatorSettings[1].channelNeutral = 1500; // make sure Aileron servo two does not go to an extreme value @@ -184,7 +190,7 @@ void OutputCalibrationPage::setupVehicle() break; case SetupWizard::FIXED_WING_ELEVON: loadSVGFile(FIXEDWING_SVG_FILE); - m_wizardIndexes << 0 << 1 << 2 << 2; //2 for servoCenterSlider! + m_wizardIndexes << 0 << 1 << 2 << 2; //2 for servoCenterSlider! m_vehicleElementIds << "elevon" << "elevon-frame" << "elevon-motor" << "elevon-left" << "elevon-right"; m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3; m_channelIndex << 0 << 0 << 1 << 2; @@ -218,13 +224,6 @@ void OutputCalibrationPage::setupVehicle() m_actuatorSettings[7].channelMax = 2400; getWizard()->setActuatorSettings(m_actuatorSettings); -======= - case SetupWizard::MULTI_ROTOR_HEXA_X: - m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; - m_vehicleElementIds << "hexa-x" << "hexa-x-frame" << "hexa-x-m1" << "hexa-x-m2" << "hexa-x-m3" << "hexa-x-m4" << "hexa-x-m5" << "hexa-x-m6"; - m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6; - m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; ->>>>>>> next break; default: break; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 099126aaf..733518ee2 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -58,15 +58,9 @@ public: enum CONTROLLER_TYPE { CONTROLLER_UNKNOWN, CONTROLLER_CC, CONTROLLER_CC3D, CONTROLLER_REVO, CONTROLLER_OPLINK }; enum VEHICLE_TYPE { VEHICLE_UNKNOWN, VEHICLE_MULTI, VEHICLE_FIXEDWING, VEHICLE_HELI, VEHICLE_SURFACE }; enum VEHICLE_SUB_TYPE { MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS, -<<<<<<< HEAD - MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, - MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, FIXED_WING_AILERON, - FIXED_WING_VTAIL, FIXED_WING_ELEVON, HELI_CCPM }; -======= MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_X, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, MULTI_ROTOR_OCTO_X, MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, - FIXED_WING_AILERON, FIXED_WING_VTAIL, HELI_CCPM }; ->>>>>>> next + FIXED_WING_AILERON, FIXED_WING_VTAIL, FIXED_WING_ELEVON, HELI_CCPM }; enum ESC_TYPE { ESC_RAPID, ESC_LEGACY, ESC_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN }; From 0b147fded5033b901f0d71fd1844130196790bee Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 17 Aug 2014 01:41:14 +1000 Subject: [PATCH 038/203] Minor formatting, add wizard image --- .../plugins/setupwizard/pages/autoupdatepage.ui | 2 +- .../plugins/setupwizard/pages/opstartpage.ui | 2 +- .../plugins/setupwizard/resources/wizard.png | Bin 0 -> 22382 bytes .../src/plugins/setupwizard/wizardResources.qrc | 1 + 4 files changed, 3 insertions(+), 2 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/wizard.png diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.ui index 34c29e8c0..782d24842 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/autoupdatepage.ui @@ -21,7 +21,7 @@ <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;">Firmware Update Wizard</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;">Firmware Update</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;">It is necessary that your firmware and ground control software are the same version.</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> diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/opstartpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/opstartpage.ui index a87c2e18f..589be9eb9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/opstartpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/opstartpage.ui @@ -39,7 +39,7 @@ <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 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;">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 controller for its first 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> diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/wizard.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/wizard.png new file mode 100644 index 0000000000000000000000000000000000000000..59bcdba13df4a4fd306a438220723869635388fe GIT binary patch literal 22382 zcmV)wK$O3UP)Zo!`L(jOfj8=UP8zv zof|?DZhG=1xi|f$64FR=AtaCx5(ohjLcsK5V`JQHS+Xoyy`6J(>XiNcF{+ki%h=*x zAn)_cbEKI)Gkf+sYwxw!T6>L8(qB$j}Tz7Fv>_Br^{P50&fb8E)pc~lO3AL>dzd}m6W3ua|O!f`l zOc26zdcarm^51^F^pbU_EiEW5bc=IN?LD*<5CzUGfa~T%>@gw4(n+t|za+|r5TSQN z;kU1U*P5d4UKbDjvly?(;Lo=|#ici$L^7peOO(ZsbV(o$+}i>@mrJQXJ8AX%7f~RD zb1{@Y3hyh4gbaG(8Uuus6s9SRWZ1eV%xIDZwhZuxc8FglW#;KgspH$7C?P}yqOZV* zrh=ETrACh0FNDNyyMcXK;5P>#zDP=WXn%Rkcw3KALI?#y56_)wefMUQgu5U%Pen@^`MY6w4AvD7^)E7I*>xMZgX3+IC2p z3KeQr3gNl_c-Qr9OOz1atG@WrdDmZkk#zjj?#PPF&o}xog^3xwsnuMUnjE z%NywIaSuBy1atu_?J`253dwaBjg%_C*W{d&YD#?`&v%Yzoweh6u{RIGKWk_@ry!ZC z_5M^~@U`u6fg2 zeL|#tr=QTu`D=D?>au;@@~v~#ROY}sAw-pwvf+5t_-#j&5Y7`|_Nr{ILj3N*3=jUJ zmi^cSPUY#1 z)quAY{_+#x+~ZO2w-r%B2mz5h;GKopyuvU4P(I>#Dy1@@eqVJ#J%(ZNonOu)nNm4z z#X&ah(0qqpQ%e1DV2Kdgx@TSq{GvBmQU(Yp6q;JJR0y$5O8LsM*8OcZMtT1YR#rg( z(-iF3>mNLF({=m!!524UnINU)nTj4g&ZW8C!^ny5AKGBgLMdhY5$<&o1U?Jy#b87rag~(DgU3?;w^7#@`W9SR3MzKP z4`Iu$5LkmkS{tl2TfSJMVCK zTXcOwh^iBplwam{&2=29tdwx){Wa*uSWOf5V-qzYNGTIirhg!%am}%i1aA|fAoTUG zd}4mVrRN@25C-v^2d0g89S8VkAHRA{9B+A|gb>9LTr+#R$&FVwjZ+5HVU~&RxO3Ri z;bV9ZaLk&NiXH)Pd7>cnWjMFk<2G5fw3qoa`vBYeuzFcH-~7}zKKGHGSQFBz0)Uu0 znYA4cZ)s)1wzrjC0CN<#s|BRwi#PA3rOm-tYBi=uNR?j0pd=kLPhw6HA61!uHjSte4NtbZ}a4gawM!xW6{;=rL<=*C!6CT%Qr zaMJOX?fQfe-o^7`*Z=4%Y2`haHV;aS?4LWmvNgn&A3cFwe(WZ=p#>=zu#N4~g_zSQ^~%Ic*pEST9jVxOj3fL|3t#3r%gW8y7Iln}xR zjt~9ypDVTLC!ff-e^!MpOEzIr!p%3-4m)G?_>{_MeDdF31z_HcF23=JrF9>Q>9Eak2b%r-;`g(;^ro}9_u=V) zq^ZrvzhAqFC3D*P&kO=`JR8%b;Vng!?aFYS0z<}wn(8!n-CxFI&lHX-Zcr7*m#Rgczyo{?--#vyImHa{>IUp z=K{Vww|;9irX{%lv6(#Zcn!fohIGaSs1peSJg#_)5#{~}taO2G%Zr9|UfmI3DAIM} zc;Fw?IM8gLJ7A^giM#u+qq>fF&5wk)3{gUe)n}Y^dhvqU?W{Smn@}Lj6(5;Dti;g~ z^~c9*2LGO0(}|Q8uk9Y_KE0|CB0L$P%j4lKG)Bd4{pu$xg5Ud6EhR-c-u1zSw0Aj= zeA<|h=)=aXeFwsP_f!AC<1+g9gf-saxzt;NC?SM%{;bfdRm-x}H@Z0MnniT?j_=I% z`wW)N?`EP>)|YnTbm)Bgeb4moiTd~#QLhK;xz}I1Bmz)TnxnKRf7sFmksR+j=Ku?5 z^-xvTH=#T1u8(oed0RMjc|8#Hg5wSKOT8tC($wh3*S*8eiw&?yZ%(oy$@B=(&6Eitx-m=;uyO-++807Bn6Q^ z?)&e*0qXS0c%Jd_rY8!#R~=}c7kKyyyCIV)l^Z@ekM7>_71~^0VaWyO(U*2Gb~xoo z1bjK>Oz-H|@+Hww8kf_0L&vB$eE_Bqg|EQpmV$?gtP})^+hvf=i6fS+ERA!+C7ZeQ ztk>|kv$kj0GO;X!bsr4vuRqxPhK*Bi>Uoq9q6FrY4lU`N7_zz1L72l)Q`N(*?|qRo zPpSoJ^pj&d9%cW1iVMUWYMppf69u7vgEd8}DlyH`N9WE+j)*UxC~6xbeC%s$sVH4e zWoa+vB|TIW_i)J>TkyK=xm0mfbqFB>Qp!VDvP}x!)MM1N%Fqoz{IW+?m9eGi16S|w zcb`ublGRI^0m$Su_Uw=G_zTncpFc0*t3Q1Q2U^2`WN$+u+iGJLZ{S?&O-qyzV#cxs z(+mFJ_onw-zekd#D3VLgYN4z+JI2{|*^#u{f{rCuBmt+ z4*d_b^SbSm%LhaOpkCBcoUCNj`Iw|_J|imb*{XynGIV4Y}y(?H{jegZScv9J3ST6ViqV&j0zT{&Ahtw3{mOK@;$9#i!1snt zdf$}lxe($6Soo?Q@J;3iDlCtN*H{zM! zq!Q)+3A_-6#|QW9A3Og45Onu%L(p}2-{)c7YFM)r45fk{4RLP!eFv%{(9Ik*70q0A zb~7h07To#QMmB77lFF0<@(mlK-gHC>Av91H9c~`<`mPI#3Wi!vb%nPr`=UaCD!>v21Va(Lo`EBhw$3z} zJT$g}ra~pI~;6pss}1?Qgvey_cqvBEA} z7?waQ5by{gyi&^XRmi1$G@4=tTAry5RQ4h4f9o*aln-!obD8o>W) zqJ$7WU=FYpoQoiMHaOBCR1nhc0;K?he&s^gkEAM)S0N=PYOEE)&KQ=@=fTS28Me5l zu@#!zq3lxFSr6rd;hlyC>Y*uKCI$beh_Vy!Di=cZ{h-c)nGRL05T;oypitQJpD^IY zPGp!lWJ?2m(*8{X?G_{i1W%T!n-po-I1x6sk;V(YFTL%t%5k$$65 z`^2z)V(3^xKs%rL;HxD2dgX5(h!gLN(@!4V@jOyOylXe4a{SjvhU%Ej!|wg?@^+YB z0W&Kh8icO61jNEOqMiO%h!R4$zfkVXW^VKe){#7 znYHEuMg~w0IQ+y>?h61uEUSYr+|(>CKC_T3ZoYxFt9P+>^$wodp!4zXcM%PxST?7F zb5BxOwa{XAHMpIyXr{e^?b45hpeqhwy&=xSH=HOTe7}Oy>tLM*7t$YePc~=qVq4Lt!L=v`qFj zEG3b;nncQEe{%;9JlR0dw;PYUjgnZNcP!UAYgLYw^C9Gif(Yz60ARf#s}J8WTb~f( zG6>%dCp+O245hjm>c*y&^s)c>-=k@^)#0j}PT}6aRE{b)yt|8pvRrs(6L9JAK*()_zW=Mnh+y?i(;AnWQI0Ac zc@KM4h8$e~B&FoM({}eSzZvUXCoX3hn|EG7E`KT6+=tPPYk;$WnpF_X3lT~Q5!xq& z^KK!;^|oSkwCyBHg%~@J#iUD=5dPnR=PI~^swr*`Gza=usE>SWKYGJ!eB(14@VJc; z=j(>T_wSg+SAH;`zLdhD5^~zgRvx+Y38tKI5t?Rj^72-8*9F*F8{$w&I(0=Ow}1KX z6oivlmVuP!h=7&dbrC-P&2??%h8 z0}gEIVOt6Sk6WR<)Jb_s5YzPY^vhA80Q>tH5xgFiPk-+)Z*b_o0q0mFDEQ) z;@S&0BQ1mXfAIqPQW^nYhM+G+z@O$obBMn`H;coOB!r|elAxxtgTAzr*Y*@0Qhqef zII)iRy=xO!-g@a_TF(Oho`$+LQpyc5sal`=7H~{~8v&?q4D!BDolYo_LsK^p_1?!P zPj*w{vpogP$ysb^T@N&46Bg^QUbuf74v9VC&63IXu(!UAz4a}?R_wP|!=4m7$!0aa z`~xS7aH5C^QWlUmi`aJ{!X;}pR8{hi=W6=1w~R%|q1xln-%?6WSkS~5KlBf_*A{X6 zy(`(Ut&EXc>1ZsP)y9d7ns{+bIiWz7l2{9|a0`3uQ*^{LKq3#umj_6KNtGyXD@2On z_YCMPn%2vrSzjm9R>uiboGhOez-Q)>{TZXa{G_CzcR!$GYlSiF`A@EY%l7|{wFtmL zz*S65G{~Y7g?U8=G4GJi%97BVG3d@4bfzUuacE6Sazdvou8=nrOzFq8qGXL2h84gL z>hxfLCBVbT%$fFYO=UaZ|I~y0?b%t}cF#&i520h%v5}XzsMIy2a61f& zJq{L@Y0Rw%vbohV|GBOGhUR$BZ$`A|WDsRfXtgAq=76sN77q1Kgk1NscB+ckVQY4( zA~%f$8(dpur=KdoNA7X<^-5mq%bAmBxgb_>cJOwk?zg%@dx%L z4#rcVQEfU&MEQXPlnVGHVfRlstvbi~v)t@#H|fm`-P7$NB$i|WuSeAulSeT}TX;@gMg%BVV1w|Doih}A;(HvvXRt()j&*sTx z400KRL{9L?ZjB8Glk{dJ~TswRUGJZ;lF@nJl7C2A%<7ykqJV?czBu0xr7&YdcL^lOx^e0guY+MPYny z1wCup4QmdB5QCzC5DG#8MO9EV1y!{hRhkmRFfnxtLpQNZn-I&8Sf-s(Y@$#!1(!?1 z;dbD3+fq3SQrd*2ZQ}B}*UTQLEj3>#NIZP{yB{K+|6!=P5QtIP^Sq46*{oINo z@CIFUW?#;Bkmu*DdxAUr0;PEoeO?2soKB zdHm&W=1=o7t=x+uMpjEounY@BH_&qiM$*DGOpLsRWgWlR3Cpm^7j_s1*hAA z)1%>VYxc__1TL=wm)GvT^{m0Vn8DiF5NSwTT?QJ9tgU|9wSUkvZXdfV{@8mMGgXP6)7c_DUqgi zluM;;*sh4zapFLo42w)(j!d5&8>nguPLC~ZPPc}lDmdIWiG*wmhoM^-IRn#_NXtS> ziRw^sc^qgCyH`2bmSw}P1eUZ%x&ab4xAZjt8^)^3WD(^6Ff2Lh`fi6H;1VQrW4B;; zTGF#WPsFQG9hjLH%ZPOJ5#%VXSi}izpqyu;iG_(ksIDAUYl-(4DsEPFwg~f+C+np~71GJLIto{X^s6{@z@SH&~*!0c3Tn zbgY9>@8P9tI8r%Dea>WmH-tS3MSeldr=a}b;tar6UQ7#pSQK^6kTmvMv?a&xz6*W! zgCuiiSI)4yrIcgFU{4lNuK`Gi_GXRtuv;6IFn3x^WowHu!R*Mkl=WmRdNQDNnG|>x ziv5C+=l@_Jm4u#*q$O$6osr`jDFQBm+hG&6vm?D9cy7E)PS#V_VFxX+r!zBVuyMd8 zm{q79ZvHtgEDPHEEVj0qyn4`}Gi4oZVwOpPZbDPsVq=rR_BMm=^!OwJlm>^IKWADd zhxwGmq)3#MQVJn<1Iu@Ir29@N4~$tZ<`Yb}RQ7eg{(#E9yku9qiCZ(Nj;a*+-dG9C z8IrEFq&sa9&&mlaFas`hs|?S8n7!{-)(X%Q=+T^ zyV^|(e3I!g6~}Q8dhUmWWM0yhvgpo8()ptoWuH?}Q#i7MF^}fqe~~ESIpc_nl1l>$ zQIA4hmq}Op*e0-@DT{d4qNYG2<~@EIM>-F!Nt4c$MgABfsv};7Sw$+^Ayu1S?3*L( zIO#DlnM5@JSaM?Hpi6@}#VTECL4B7+)_DDcj&8!vHiPPjLV5W0iY5f))e6kxwUp7#8N5crcuX_>F$St+o?=@-6>*T*jc zMiDh>BX2fuEsFRYyyw)ilIb-8X3h%Wc2BIq@`fatmGtE#`F@gwu#K5Vi-U2CeO*V_ zS9PT&n-A*8M3SmNv0q_nxyFowBa;MhN>!)~JBDr)Cd+#61sbD%NAw?`T54*lPysAU zvU_KObb9QD%bU>HYg^Y{nqcY_7t0m|nKL6mDCR>rTx2o^yZ3anbw@8d_oj&Vjc?%? zju{0S#epLe-IkQ>?VQ*(4+pP95c3HNdbeYkE)D--8m%W|vG*vZ3W_2qi8-jL z_OfVRi1K0=U0oSk+w;7(GeK=*j>cYts8^vnqT(Gx|5b#bywXEKp__eslavOWdk-e^ z7Xm*TUhcR{l)ZG5dZ2t+nScF9R+g<%RfY0O53!gFA)vmlkM1tp^e=(>E|Zpo#p;EA zF28g-j>;J*v9dvOjtD8SIvc5dek*tXv4Qp;eavEEw_twh*zaaWmuzk}jyOf|xD-|_ z467#gPR|BhYINY3q6$JG2Tq4VTU!<+ z>})rQ=PWKiyNHw4%|or4Z+i+~4=fY2{xu%?<2D|7wr4QFayXVu(Z=kGwzV1~JkJAg zX~K@_5Q2AKRLqhUr6|?&5rOEavSU`Mvk9wl7ytNY3x9p8hp-oB6>2B~`~i(wvx6Wd zdv+&DCJhofv+HAz>Jt@V@cF?YH^91blRZ3J%?pVdb)>P(e*th zy;+NoTs?)^YnGvu*g>M{zAUdiy&IX$AoUCg72$N_i-uWx$_&Q&6fP(#>hvX?cdef( zC7bx={jE4PK}H`U;9%Th<{^{KuCz6RBmqRd3I%>aLyv{mt8()Vl@!gX;Xo$BfhX%g z-vNdWniHHJ<}9C1Vdp03vTVe6qxnZe>S z7IW^&Q8I?4I3NbC?HwtLyg5>Gn&U(LoyQ?qG(}@}kxFaALQ~;WAE_aB!fMuU%8=f> z1HU&+)tXyqFz52rGh2|Id)WWNMqd2qwz0qL=5(XZT+X~RSMuSj%Sq-e>bp$haf9t! zd+F)U<94eAgAM`#2T_mK$stMbkGFb$A@+FRx3JhZ51^qTO(L$Nse)Iues@b*NM*?sTj6Moo22vb;cLqY z&Ys7UkL_h{u$>>=^BS=eZ=z=5YTkXzS9s{<95;S*JNG`koheom&p)gx6nUbN|et*JJ4Wckpy zx3i!k$1@LYJVI3jYV`uHxvUZ?1zAH<9kIJSW0-HHJ8fIut0F4XqPCwaZ%PjKN={i8 zq-t&@yP7O&A}Rj+o?4!GrJGkb+V`%nt);ieUV;6W=Q_CS(R%#34i4_`99^A$C>3*9 zeR3%?%3bX5ws5&s6csu;a_rm|ClS}F2)Q&SnW(7%Crk;9a(<;#1|97=T3T~7_nMrx zJcMWJ3_A-4@XGq_oLHmtgQJ%V8 zEr+j-<{(s4!-)(0H1?X51_gya1!I^7-j%i}@+(w?6|{Z>Tw{-g$0fM%+$pHl^J&}L zK%%#o2cEIL5VwBl!(4FcshoS#$s@YDyB=*J>P)eBQ!V2{)ljP!aMi`7o{pX9Pqr zM$xRP%&2hD(KmWNpxeQXlQTy3&!5Tx3cQZdpO)!IXUd|y(1|lvY$tcX4v>_&3=OS^ zf4~8>_vFdtP2>?81OP=PP+Ck;#6bpu$E8rH(QDw4I{Dn#bGgB4g$h|ZKS&}gF%IF%w22zAlJR&-R5^CQ zc+TTg0-=zD;u1F%m0n^6E;LQ_$A3!}%=RH7LrYAA5J;&owahc_#fPIL>cZ<%28lir zM7WUoHC`Iqb;|nh5ezv{H8H4(miF&Y=#sEsp`gfzaCr&E{KQihbE_wo_Gs=@AG)RB zbRFTd^xhCFmW5G-pf@v;seXw{4c~V>i5f7FIZRXP0A*z!ii+J-PxUc>K^Skqfs{~P z;YIj{<{Ux@gxf=9k(((6NB)q^iSt9~mO%4Pj9B3dQ&sLIr(1*~F5GUFaM*6hXv~S< z?;sem|2Ks~B%mR@wpZHYb&|21tePJt8a#aCR~EThFx8K69l2h@?Zx4A;BncOdcWU6 zd8Li-aeD%jw{&H`btxQ#nl){MY+y=+hne3nyl^5Z(|TmqN~fzLZWf-rrpc1dteB z_IN83djM*?GA#hvjLCt96nl0h*}FSQOM4DQKq%(n(5RM`XU^lD`Y0vp7tD4|~bj?9Qp-o0QYY_}N1~ohcxIIJn%IOx7h!dPcsasB7 zx0q-4I5>T2l;3@60W&K{c7uy+0^I-AMJ$^gX7d3TE7nXbM~HBFa5)rvx*#DQ*Xixi zN#(48b*4j)FtI0{Fm?k=pV}YKo?JDCIR!f&+sK=vZtQew)U24xOIx;c;Yo#@I5)%- zo4VLum%{5&m^U@R*(+j5Mdk6=6xO|a*~DulC3@bLXH5~jyf49B&o;CDV2V`MM7Jah z%l(`*D~uBd>8u5rp-)C=4wZ$cE#k>%x3H=v$b(;7Oixm0e`}WMWgdb)jbu*YiCr#M zoj>t<$xM=L-okxIU};k#r*Vix9dDwZ2Ck~_$<>T?(5czkZ93Z1R7h)-GBABkDPEtG zM<3t9^64s9o>2;C*vBjhyIWKarv03A?Q&f1BMjEVq37uC&S6@T&)mP4?!G*iEiB^d z*@dV=Af-iZBFCo2K3=R#aCvSD*QQ6b6H}^V6qcRJa}U3Ynu`9RI z^T8w?omtBBS%hnJ+)HU?jPtI42U|DPv8%Zkk;JtD4D_C@E!^5aMsZ1%KV$)pXOU zDK#@@2JrjseBrsgg;N!5-`&UJcqgK0?8ID(Dp+*l@%xyJOm^|5d-hNqaN`nAbklZ~ zkA-;!9{%H$a=!Z8J)C>RK`Lv;p1Vg114IhPj#r#eolyl_!$C=NdS#IR-guB_)^FjIHH%)?y}NtUJonN* zo_=v3yY{vrrDVpmA}&3plwd~_O&vOOibqngt22`Y>ZFt-EW48x+;TPWTOsKD$ptff zPF0MU0lv~?5R0l9rG9?>XdQ`UhPgGi)v2Q=O-EM>T{l^=q>44GXK?DO8ctkRjpt|- zh<@~K-$3=nzvuGVl{hs?S3XBbbF;ic8x;h3D4sl!z*pwuhd=(vguTv&VeyB*Y~n|E zJjJH1P53+x=FKc--t;iJoXM8m9csIEaCIFoXzy=f(cbZ_Vw^T_iko(B!DF)hGNp(m&F%w(a>cwtw25O8ii>= z7q_i%qbcy=ch2EAx6Gv~tRTd2VW{N4|4`4D?%9J= zSj;Oa8mvPyXLk2yjm5zC554|mW^P#vJO+rX7Z$y+c6xYKMz{D=Z8smgd>UsgomgWJ zpsw5EfsF}%{@`v-KV>GLyZLOYDh^`-$Y;rHd7cYD`8?%54=zQcE)^$Znk*@Zkk1Q> z{K_b|{Gqt{kve|y(S=-m#mOkeQ^yRrdFG{kT>Ig>m{uO*mUm9)oOw>hj)#STWFoiz zWG6rVdjmJGn!=(IdjfsW){dwDQQNZuD3Vf+_)6xa1z<`k9|yh-@VnRA7aoY`_HFJ= z^X(7M9VE%JAd@zT_vVTBKAJd`=A3rP1#_z2p>M&Sz`Zu`g zGxyP#8e`p;X<*iF;+J>tBb_sC11?~ikWMT7y{-+1W`_f8?q9Yu-s>9iIQZH9O>BR1 z6Xvd$klCU3lTz}{+aBkfD{kk;3up1z=jUx{d zI};q--^Zsfn@VNW&9e< zNfM4ULCb}qD|F~-_O<5-`4xn)SX2-um$$FybwYJSBYMcfg70r=rZnK8(&OjM)ltq_ zTZFTGCUJKW@4o47o_l#8zx>Qsx0&dknl zJkvM_xKK*@(5SYY{4{W43a}Fh+;B=+?X4G8*Jzp`mp!^15MUcJf?*fYm>aEsrQSCm z?cugRY~$$%KSoW&BDMQ9?zp?2eN9=`ofzW&S6lJqoEW--sT$P9Qygg3aXFx{Km!xz z76egD72TACJ%Xtb6<@zr_`_G4nOpAXtQkeTu)PnTN9DAYA-?)xEuBf7KYn2ab4uOx zbY+ zJ#%^T`5tn4i_1=r(4EPnDT0BH&8KSY?@poMB&S1Di$P_nh5|Ha`bZlV4yT_jt&+;H zLU~98=~=Aq4<8M(A=0BMUv=G|06U7#UU^ZNj7be%b2552zmVu^Uhb>BEZv9%D<2I z%*R!t>||Bk3tX%UVXT=N-m{=M;5JOHJe`;2B|h(#f7G>2{oM<#Gh2Ie`@VJcjA;&4 z5&4|`psK1MRDm=lrg>y3lR$T84%3u8`n3}{{ZlUxErhd z=ajg;JiEUcpTmJuKzq`5u?yhw+74k~Bh7;J9JbLk22y+;pFS?u9E z|2Bt%4apJ8j;abAE(N3@pEEK0$Ed?~?v}K8aesHSZps?qpND(a;~6ud0Cxiy&nocl z|IRtnjisg0nTd>Ana)cEpd#p9bpDL876Bbk?ChET$-8&AB$F9yfE3fTF!FXTB+aR! zIVV=Vcu$^uBF_&#FqiNC?EpV~qJx`1`56quz_Kh#D=G%9?UsbA7EeXjG`s~x=t4nL z1*#%Q2@h9%=<_`M*c06T(_b+6jEle*BJL>Vn-4b<4m`_2?X{9?TF$FuAE7I5jx^5EW2o>X3a zFfQF)snJqV=bZA4B1Gf*-SM)^ezLQtxhlpC?XxoS77mAk$Llzv z`ydg|Gb854>sEPbUxJd7lEF}}%P+s2O+DtIuQHd(ammye6=ApiayZ>6n!@bavpMOc zldvp{TrS5Ymt4Yax826qzx{ol-EVNloG7`BiQA*0s*ul_q|*lZtjW_PSXx-90wtn zqw?~(6)ulMeWj&0A3OiHo!)ylbT#z$BxQG3FS%@f@UeB>B9qn;NIYH@$6=(bFQM~= zcTJ;YN+pJ2VD^8Uclq+=n1Kk=Gvt}oO^Y%!%?-gooQVHFk@ z5)1~p@dF>>zL&enW(=|!W6baVP6XLZmhPTD^NL^8TGC?w{DNpzUtZ!+h4}dDiii+= zRS0p(q30blQFiWFegr5tE-&@><)!ExLy``K*P#|&HLr5n{G!m)KMMT>&3x0x^vi{73%iA2VF?{Dhk8QnT~ z>D+Q32;bILgH%ou^{U=$7L_yrzY#)=$jWv+B|beVDgXJkuk(1PN!H~ZQ^PEGTkPMzf5bj1CBMDJPuBj?CT$&OYQC64K zc9|#wKEAplEMTn=;vECWk4ZfjLO6koYoeZpl7Loq;3%bO#I-Rz#TT=2<3?IqTIlTTB%My<@pxD=Wy+z?h|A?-qPc(!)39^=WwKb7MP6!|_uf?} z^M>WU>pfH3!(KIT#n0=_tLBgPZnyVY6#5jRUe$MMb!g91`{Q2+PK0BhN38|ID=UJX z0P$m7>JPA{s%T9z-~4n(DtGFQCl&7f`;K_vo|ikP-1BlLRWVoZ=hjUzrbg9RCX*GJ zOcq5^aC@A%-7XwX2aR1hqR}Yn^yptMnp z;?+2JW@yUq>pu4S?2^XG@%r9lzMr1Oq+DhmP}iv2;!0SqT+yuT0KCxjRw ziCee4%EHniqAbfIpEt@>-pBk(Px(_xcvhM_rnW$+1g+50lXUGYs zbUPA+K)qzvlzG41b|C&*OTJ-Ysk7>u<>A0J%fqs+TW|j9Q|UAn|nh*kiz>Cl49qc_nbVm7-yPs=Oc6KIS zoKp}yarnI@(2|r)iwe%FiR6B{spVWa_O5SQz^V3n9U^?J8BPv`Lsk5zRTb{}^q-p+ zJousM*+{_aHVsoujmWZZUR;JDMeenO*_QQt62^12eI<|Y=q-7CM=x%-o7IhtELgB$ zP&KzK%TBv}h&w$H2#`n&MP&^fKa{B2eRUKsFV45cjZA%aF0-*AWj(Pg9_mRMK0p(K z$f~LS`tMy*{@=&_%bwT{?KU?+;2 z44gB)WbtpeHsrRqWSbUiiHc}Jm}o47t{Y_1Su&X{(vql1S4BuIdH?Dt`RDt1ZOf}v zRoe@=hmSojmy2vRJLbJK&2En2l9$P3C<>^lYZetX&n$MkDe2XnF?4hyCRsx?()_ICGepH~=MWl7K!SW#iup(oS7zBl5^J<~wN>z+sTTO>4} zQ?YHnasDF?iz;#PJ-1)0J2LB)4YYa@B zolfT{Ezs?D5B@!Xa5#)dQ+yZ956qZV=&0~$G9c~m`SqXUA{-4;R2(B1@=u5)07VF8 z-SWbwJzYcD`s=%G)0+g;{yN0mngGJbGU0Usc>7b}PnJXhoH!*qyEknHcC_Ui`}#(z z-9iXFUN_N#FhwOX!jT}Q1%A3Z+XuUz;gjBham(lPjp&+uz99{4`2JupNKb0mXBt!m zx5q^&9H6i`MmQS8?RJfy`(hkemgMSF%N)Jg{2bZ;#T84!jy97G2MjX0g5Rl8+nq}R zp<^b>*Pm)~GKumzwUVIAvEeI!J?OVgi%e$huFIZNxd?{*L<8)W(x6LY5c2t|Sv7DsJzB0)S}_v^}bHdGJEiL=9n5~9t?%=Y2O@}{IEDe*Wo z>Uwesj*~inCSVTN$ps@PRyr~Ob)GNH%)T{5td~QO4Pvq0f`#u##B}1 z)yuMQ}Bgvbh2$t7`T3Y+Eqn4-)52Wse_4PadCJl5Px}px;2*_vdKva9IB~f;5d6|tbzl0EC1Q7uFLvln6 zKdvYWilT7eJ$JHho~>kf{SL~j0;rmTd6;fq)fCDqe7HRt*$KogPA&E#A!1lE4fa%f50xogb1c&26Q-rVB=iYMXi=7_BFfoRuU`eHP z%Bus!3fu_nZsphSoz7qGy<<#`>`*I(5MqQuR#jDYY}>|?ssN#gld=lm;5q@Xf3&11 z3d9QCRM!L$LeSBA_;GZgO4Y^o+m+1g?O-R>nif?#p~68=CQEh1Q2=xu%Y?TOz~fMy zM>{^12JP%Af}{TcKuy%|dakjv)Q}>Z%jVpg-(KyPO`90HMYPC`FX*5zp_54)%qa6? z7{(|?z~yocDi?~PplRBm>h5qjSpVdcoV6fA<)`;){dSirz-F| z1d-Q~m%K9MtpV8FlxaD1oNDjS{Ni$}#ERUMSNkc5ILKyg-_U?$IUJ5bjSpUn*{ zxRdVF>FylqPm1~!lF6i<#;5-^4+d>R=zu9H91aiu?Ql47I-RsMAEdf?SpJD4EK^LS zbQ~|77$Q@#w?QYKy@5v2zscRMlS^wC`n0t@MCLoncp{goQ zr*lxE+-|o`RBJmGg|ttCTqLkjbCjR`|&f-we%F$064?Xf*J!T6itvCZI_W$*-#KWsi52HQ9c z@PUV5Gk{HoCNxb)Islz2=crN+FP!=DB(+qzq^frBwNzS5s`uX2JMZ3m?z!jeol^7e zm_^`7YLvOyKrwTaU*s$$aLC#uJ<29ctq;`~*5OIJt}ZLXx+)Q>PSD957Q;yc9}Vae z$ec2$bK7yCKTygTBTdyAa_Sigz+hh-f#D>aZW&8Ttk}PAAGUwx_U!*;=BsElnq5o9 z<8cUr0EfeYWHJeX8IU+fU^t19L32orhE>EO8YG#4a|Xj8q>_b6RAd|zi_9ee&<)Br zlmx^zN&>K<*rCs56@maTzDIG6Y1Pw4qJ*|lJ#WI51O_6r%J6XC)J6h;I=8I?0OA^A znmV})tf~e^hZ6_|Qn+!87mq*so9rT2(=@26ic~5EK`@i|qtPgAHXCGF#*Q63aQ<=+ z+FL>x9*pNXJVd5(5^=p?BLT?D>uILS4XmP&*HtY7LnNhT=+lZbl-nZ4fr(KGkCn~1 zpzR47*wdw;XXAKr9IWHc8A96}l`OLs2zA<_hIipzuuDvjoO8k0RKklPHo2 z4B*TZF3Fv%7z1qc)YD{vMKXq(O)ZsX0BR};S(c$`T6Xc9>0P2ILKHK1m` zlP#wf(MNmCM17kmWC@i#3h?1zER&@13Q)MAHZ+%5yE!v82FD}gTzC|Q^))8h`_eK2 zXH|(4gSQ3RO%`}6rWy>uB>PAcPkQcRH(q)1c_@lvDrOs*-e?Y+vMgio-n}@x$+h6p zv3Z8-ibw!plZ5Qk;Z^|y7yRfrc6Eg;0D6h&BcK37rE?`NUti_UxS@Ff02b3pL_t*2 z0AR8nH4r|f;wcNJG>;-N92?a0hDip%HWPiy6i{`NqAAl*;{$6Js{nDF+u2m6AQm3W z?m1-)lyNF-HXHu?(O=`^t7abdWLZGLPZ&-)5&&?lC+1+lh|40?0Orz$5hXi+6%FdR4> zgl9*sJsA|c2q7H|=o*NR8AQCsWy=OA8P|vZcyhD}Cb8o0GoKe?sB70(I!-DQ69*?D zSDy=^e&QM}w7>XK`=Cd0_8US~dTS}(emG?c7SzlXKXGc$01c|g# zTZ3OgcTYPcNy?@;bI#G--HkPkE>zb$5DBNCr3|PlL6R8kP8oKG2vOqDbpvCglS;YI z8o7qL{|}u`0HIR5bqN5BCDgV(z2Rj5k^p|3d)!=CI^XtK#nD=~><=ZVC<#`;yuqTt zu(nb_e}v2-E4};s!NAly@^Muk22kNu1RFq;E>6crQ>du6p|-&ZHDw?cRUwKTtD8Is z27@RsF9+uw4u=DOeD3$SXqC;R^07~TOUM9vyP|oN1#^W}5wZ*2XiQ7B_Q%TYlDLNf zX9K`%?E`&D&1eMhOCrkCgz`5JkRm2zr`a;FW!NTdVkyT=7@Nz8j3vkE` zM+dcOvzj_XvG(+F3NUe79RR|?RJJEcGKbr1f!!(L)+P>CX^ry&7z=sCUlJH7>pRu46`({b;Q8IUTs21YCKv3(Nu{|2rx2401(8<=azxK zDB|N1OfFsTN440EC!hE&s;a6G3Wea540x2uNgD~k&_EpFS!#1k1=Io6vxjlXrI+E}|M*v2yhK4qOAv}( zf?_j=Kf@rXDII~~6jH@#j;G;tOIc<#O*4$A-s!IwIXmuGEX|L7(0RxpS_k0wMD*lj z$Ioae#@L+#V>kWXxwS)13$N@B8j~(^$HOYIY_{ioBBtttI#JU_OI-oLG}26Y-;uD2 zNcdDB)}sjc%grUY;d7tH*DkKYXEv6Zi6mha(eU&tHHE@ca!PaLwF4tvDb1)~>T~wJ z+}7Wh(DVxc8~||BRL4(iD8|?=9;^8E?_5xy@Y#gQp@@O@(b+v+PRqg=sx=TfDGSWy zwK6XeL6i!M{9eDshrihDThJ(Z28vzGhK-1TJAUzz0zelzXWgOr`7jB-E+?YUROguV zS2D&{1Gs;6xxMOZo2tAPkqN_51IOneCS2y=7@5MoE(Rw95#!2L?k*x)3?MJje>#XF zpOAQRI*bGW-kjdl+8Z5hABdH4#(F*&3T}X@S$ruGP0KHy_bVA=8v)!>XBR1K3P`Kv@Uy$mYShGLA>Y^`y9yzkO%(|%D!D|4sRw=iD zZ8{`k8X6b7!8t>4G&y6W&gqij@mbK-Hi6!CPVkqXQq74(wdB(~`PA3u5nUH+DIpc^@3PfGEfbIO=4JEB_f<8=mubyf$pGzkphgQ8LW>u`y9FY&h0Fp@^r4{T338weWjzyC6)ArOy{AHd8VO6Kut~!f~uQt{cH%W zCd2FPgKv19RR1rZtZdAD<}39=nu9Z8cS@+L&0!c*btK~kbe$kc9I};Xw@2bJ4c+a< z^`^QeCoEReiHO9sRMm~Ia!sd`09FyvoW|1$Rq>3mn*e-&iBC!0w64PKwTj*o!}^?A zSr`LK?HnQp;u;}5iRj{NF&a;`{{C1`&C_3LPS_>50Mjk^m(5Q3EEnZfHn=>~OGzYR z8hVNh7rERr%BxSQ;N19w_fJ0cPX8hRpPg#0G#w_TFGy34-UQ%V)h>&4-Rd%UEOL40 zm?6%!yk;Iij~wnea@k6k<<|3kOEMpNye?Rkne`CIgL8)3CP#YnZzAF`4ZWR_q9Wv? z$Wh07hemZ#Zh8WtcF>VYO%+84T|13dOek?ysAHG-Ut)I9_?Au8*BZp^35}4{%oMP2l8S!13PpD) ze)#3q{zbpKsWDXPYJQd{@WY}Vhq6Y@lr!`0ZS7)Swzl$ zd*!0am42ILQhmbHiH>0Oz#Hv@4Zrw&W2!30NP;N9=l2#x8?aE|oS~+{k@fO)o#?`E z?&{umGFS`XdLnwPsPh8=5hXQ)KL7lQzV4w|@_6yhE*uB?$KHOueQ?=twm0dyMq-S? zTjD+=jl>vGS!2r@2>|}j&ptevHqvv&8VMNZ^)bfE1kN7X)>PhD=}=Y{d-AzJCrZB3 zIfY$BqfXT!@aL3|j)l~C(_g*L5-CH5DKGT=d|hi=zCOm7 z6~Gq-&TeY**khZjeQPZOpWw#N6{GP~+gqJOJ)`l|#_e1EoqxW;)5M7K9t262;PyDD z+`au%f-#`1GJm*>#x!-^?eC0r564RZ{4Ejva9*!DoAnoCOakzi4EVa=ZV9d|b=&J) zwiP1J7nz(6!KB*t;ZUfpZ7k|aX!;UaWGA2ea`Pe!r#!V`LEvz>>`>+qa6O$6MUKi^ zdmi~nAef4+x$UjgNJ#YnxRZ$PneXe)nE{hAwh6#z7;u$U6ykMmTiB<_7D?cu#JMO5 zOfm>G8czj>V@Y)^p-Q2oTB#E`06Yiae*nA;K)-gK_xZ1W%y$tHF~%6|4h43HZO)Wx zrwfWrL}iT)LQYb_O`dBSW>sZ+*_Jb2&EVlOI6wg;4GN+QmbIP`_c3(mVOTd zcniQTqI|tF##r^ndi!(tTwA-e)aO*@lf7#`A&ML&WmdSy1#{ncf28Z`@9nMBbkbn1 zm43HSZCG&Wycrw7Se?k(FSo7s3E%xx(`Kv0XFZ%QG&pA{@mt{W##3H^YX zm~yx^G;rlV?XixARX2ba0NhMO0}I}!Gr>?9FvcziaGxS`v7ItcSvx!B-kBdo}iej8pgA`20Cv4*@q>gVbyIBdE)NRE$X>& zxwrD{JKsA%L?2s-Hcf^FEQc-(M5HmsIzE4X)zQD$T2b=dCtK=2^`nFJey6nWmP=~2 zYc`Z_-&B-k9{1TQld*VTt!>T191k>hnq)o2t2rr!1G=98Z}yR4B6 zYSuw2(pkEv3um06(kNTk=tPxEF8lcxmLq9U^ubrVo!@(=t@-X}+6Grv+fQ7zu2jBk zjc=*PCQf<7IA@S80%Qx%dzW&CH4qSvs>zc*vB2wxM#8__HDKM}609M@;%cvD=#DGv zL)%vS>S53#N+*wyS(kTO4Ryv1eE`51`@ti(t^V}tN_$>NiE-#VPXs%E@=}+0q$^Sj zz_3~P@$*;sqJOrg#InBG-*?zbM9m9*FETh&dsJ62Hjz7r z3<&2myBp8>svE?h-uS?g{==OS{e=TV#tR3A8UW08>sJBbfmz~m7-p3FW1rYinz-jP z&5MXKz2%gVWQzcQnH6@Ygb&~89RW~Wiqaf$rW&gKx9<(~e(s{`#Y6pZWORCS!3dJe zDrx{8C!)L4)%x!A%aeY&bKac*hF}_{13(86ovNK>?0?*fxRl7Os<$X2tQG;XmBV5Y zvN;d{&^Z*>0UTSP-##hMR734P(h>I9>>}!#ok+$tBohXb2`#N}Xc}%Xs9In~Kah5l z$I`Ek0q8=Xf1cVh0Sj)Z zbXe$a02=`4rEdAaC%2Tpdg+Ez&&O7Ho4gLG0zk#|XE}vrnsst-Yq$r%_X}*31YjwE zH83@x;s9cixIPRHm#P|*E~wu-7C5$LnYaJab$;B05?~+oo*uLan11W19i|5Wu;LES&htm34i0T+_I`%p*@=8>H`V3AX(3skYu1_6{|qG-C*6;q-gO{N8N)7s61Cv1F60y4~=`%5CqE5v1tT>{`ymm(_+Q6I_qPOBEv~YE^x*BQe4Cegm(FyJL|n&Ee=M&OFrpg4Z#;Y~u=`{%0pR0A z)S7OO1fct~=adKUzF~2Vzr?DT>mpz>hA=WrvPC`(dGSn$MK$zy$B@#E)Tiz}INClG z|1uFhJM)oKV<8N6J%C5|+`Ty_b7r&IM0iWBP;95F*Pnd5fB!cg{6H89t1H$uyLSKL zjx{yQYaR7doimlv5s&F61whWz9tx%~GMLCt{tUp2AB?vA-J{1H0InjUz3IBI;h%qb zMc<|dS3~Z3IcH#;fx%4OHgw9yB3y16r4>q^!LIq|eLF8&;qhF&%2(~M2yRfi4%igZ z0|PAyLJx{(GnDag)metfI}Xe$Zo!%YT&|^B@T~GR1{f|xX9J(esr*< zr9ZY|S&d`YQ+KX!XsobRPIaziLdWQE5|NM!fFOtrUY`|iubj=8H4MVYU?PvBXe^-x zF1}|UG@Y&_qFs!!p8@#Nc}u;mSD#%(G{0*~L1))#`Ujc84q~oRMUJ zY0;z}d+^on!T)-*x1ET#6?I=1XpTA;z<{+v|-B*Z5XUb$lYGVRSfw zSX4v%NTToGp6y87zkOL93^Os4a|WkdhTAJ=(}-gc4gI|_Q_L7Z$7rJO>i>AZort!k z!%JTPa2|lw09F970#ISD-G%^k0oV=Ty^pUiz33ZP)_Xl6vg6 z2R_*S_>SInL~z4g{2l{P1)w_p?t#f2@fLu4r=upA4HnYtV=x<}IZt7F^$@411;BlDAj6Lb|$N)YI;8wp=UV6?F_sG^I z9;~c!ILh6!14K+G=xsys;NL%T+}aaJK0!pc6xe14;MM0rpx^YM@P2Zvrmbo^o!=p9iPyi(`2Y;&RyzV{lNC64KU29mjHk>J(kjAePgNc z;m&aEz85=vBVpAGbL-(YBHA&{IoASM2cQ;a7^)6H4S)d5fayyBo-8(}fiYGC;4Xo) z8^3f>b?5dAs;aF5w+kYN%Pqs^5HZvr$H9(p_jUIjdWVRvE9QDrw&OGz>Usc=2%PDP z#FG}8r=khnl2EfDq6mN;Fga9TC8EO%-l#c(F}4`M?EtPTbIa_Sjin=(toGZzcG1EZ z!$Yri2Oitm-$F!JEXegw*A6dZY#V?-1JDR_0v~`GeEkT(d*c_WXDZU`vdaKm53@(t l1L%eMp#8&ql-Nv${{{57GN5%uv1$MS002ovPDHLkV1jO_k!b(` literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index 507b4c877..218840334 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -29,6 +29,7 @@ resources/bttn-calculate-up.png resources/bttn-turbo-down.png resources/bttn-turbo-up.png + resources/wizard.png resources/multirotor-shapes.svg resources/fixedwing-shapes.svg From 741efd9281950ce024af688f017b708fcc842816 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 17 Aug 2014 01:57:15 +1000 Subject: [PATCH 039/203] Add image --- .../src/plugins/setupwizard/pages/opstartpage.ui | 10 ++++++---- 1 file changed, 6 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/opstartpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/opstartpage.ui index 589be9eb9..2f161f29f 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/opstartpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/opstartpage.ui @@ -39,16 +39,18 @@ <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: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 controller for its first flight. </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;">Welcome to the OpenPilot Setup Wizard</span><img src=":/setupwizard/resources/wizard.png" style="float: right;" /></p> +<p align="center" 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 align="right" 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 controller for its first 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 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=" 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 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> From 4c242fa2e05f724913e2e9a037ead65713224129 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 17 Aug 2014 04:01:21 +1000 Subject: [PATCH 040/203] Wording of FW wizard page --- .../setupwizard/pages/fixedwingpage.ui | 34 +++++++++---------- 1 file changed, 17 insertions(+), 17 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui index b1c5f253f..0ae63ca99 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui @@ -16,26 +16,26 @@ - - <!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; } + + <!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 fixedwing configuration</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;">OpenPilot fixed-wing 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 fixedwings. Other variants of fixedwings can be configured by using custom configuration options in the Configuration plugin in the GCS.</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;">This part of the wizard will set up the OpenPilot controller for use with a fixed-wing flying aircraft utilizing servos. The wizard supports the most common types of fixed-wing aircraft, other variants of fixed-wing aircraft 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 fixedwing you want to create a configuration for below:</span></p></body></html> - - +<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 fixed-wing you want to create a configuration for below:</span></p></body></html> + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - + + + true + + + + 4 @@ -63,7 +63,7 @@ - FixedWing type: + Fixed-wing type: From 3a4b27df5ded95cbcffeb4197f8bbc6a7fcf4c5c Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 17 Aug 2014 04:15:11 +1000 Subject: [PATCH 041/203] Minor formatting of all Wiz pages for consitency --- .../setupwizard/pages/biascalibrationpage.ui | 4 ++-- .../plugins/setupwizard/pages/controllerpage.ui | 2 +- .../plugins/setupwizard/pages/fixedwingpage.ui | 2 +- .../src/plugins/setupwizard/pages/inputpage.ui | 2 +- .../src/plugins/setupwizard/pages/multipage.ui | 2 +- .../setupwizard/pages/outputcalibrationpage.ui | 2 +- .../src/plugins/setupwizard/pages/outputpage.ui | 16 ++++++++-------- .../setupwizard/pages/revocalibrationpage.ui | 2 +- .../src/plugins/setupwizard/pages/summarypage.ui | 2 +- .../src/plugins/setupwizard/pages/vehiclepage.ui | 4 ++-- 10 files changed, 19 insertions(+), 19 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/biascalibrationpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/biascalibrationpage.ui index 3c85d4603..345fc5217 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/biascalibrationpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/biascalibrationpage.ui @@ -21,11 +21,11 @@ <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 sensor calibration procedure</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;">OpenPilot Sensor 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-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 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-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 perform the calibration, please push the Calculate button and wait for the process to finish. </span></p></body></html> +<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 perform the calibration, please push the Calculate button and wait for the process to finish.</span></p></body></html> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui index 124f54c86..ac74de048 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui @@ -33,7 +33,7 @@ <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 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;">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> diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui index 0ae63ca99..e4bba0fd7 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui @@ -21,7 +21,7 @@ <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:12pt; font-weight:600;">OpenPilot fixed-wing Configuration</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;">OpenPilot Fixed-wing 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 fixed-wing flying aircraft utilizing servos. The wizard supports the most common types of fixed-wing aircraft, other variants of fixed-wing aircraft 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> diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.ui index cf17df324..48a03d7d8 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.ui @@ -24,7 +24,7 @@ <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 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;">OpenPilot 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> diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui index 0883ec4d5..092c76187 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui @@ -21,7 +21,7 @@ <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 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;">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> diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui index efff8d7d5..f80cab6de 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui @@ -27,7 +27,7 @@ Output calibration - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + Qt::AlignCenter diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui index 9265d3845..e7f65cc6f 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui @@ -20,14 +20,14 @@ <!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/x/HIEu"><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> +</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:12pt; font-weight:600;">OpenPilot 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-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 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-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 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-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 read more regarding ESC refresh rates, please see </span><a href="http://wiki.openpilot.org/x/HIEu"><span style=" font-family:'Lucida Grande'; font-size:13pt; text-decoration: underline; color:#0000ff;">this article</span></a><span style=" font-size:10pt;"> in the OpenPilot Wiki</span></p></body></html> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/revocalibrationpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/revocalibrationpage.ui index c68a19a84..173a8f32f 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/revocalibrationpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/revocalibrationpage.ui @@ -27,7 +27,7 @@ <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 Revolution controller sensor calibration procedure</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;">OpenPilot Revolution 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-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 calibration procedure for the OpenPilot Revolution controller is not yet implemented in this setup wizard. To calibrate your OpenPilot Revolution controller please use the calibration utility found in the configuration plugin after you have finished 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> diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui index 659d46c2b..3e2fe7f7d 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui @@ -21,7 +21,7 @@ <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 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;">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> diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui index 34d9531fe..b78313744 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui @@ -21,13 +21,13 @@ <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 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;">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> +<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 and Fixed-wing aircraft.)</span></p></body></html> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop From 3fc991fe2c56463099eb2932698e6792a903c584 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 17 Aug 2014 20:31:57 +1000 Subject: [PATCH 042/203] Add the outputpage for fixed wing support --- .../setupwizard/pages/outputpagefixedwing.cpp | 54 +++++++ .../setupwizard/pages/outputpagefixedwing.h | 49 ++++++ .../setupwizard/pages/outputpagefixedwing.ui | 153 ++++++++++++++++++ .../src/plugins/setupwizard/setupwizard.cpp | 7 +- .../src/plugins/setupwizard/setupwizard.h | 7 +- .../src/plugins/setupwizard/setupwizard.pro | 3 + 6 files changed, 269 insertions(+), 4 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp new file mode 100644 index 000000000..66db90bdf --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp @@ -0,0 +1,54 @@ +/** + ****************************************************************************** + * + * @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 "outputpagefixedwing.h" +#include "ui_outputpagefixedwing.h" +#include "setupwizard.h" + +OutputPageFixedwing::OutputPageFixedwing(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + + ui(new Ui::OutputPageFixedwing) +{ + ui->setupUi(this); +} + +OutputPageFixedwing::~OutputPageFixedwing() +{ + delete ui; +} + +bool OutputPageFixedwing::validatePage() +{ + if (ui->rapidESCButton->isChecked()) { + getWizard()->setESCType(SetupWizard::ESC_RAPID); + } else { + getWizard()->setESCType(SetupWizard::ESC_LEGACY); + } + + return true; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.h new file mode 100644 index 000000000..d3d99b0fa --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.h @@ -0,0 +1,49 @@ +/** + ****************************************************************************** + * + * @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 OUTPUTPAGEFIXEDWING_H +#define OUTPUTPAGEFIXEDWING_H + +#include "abstractwizardpage.h" + +namespace Ui { +class OutputPageFixedwing; +} + +class OutputPageFixedwing : public AbstractWizardPage { + Q_OBJECT + +public: + explicit OutputPageFixedwing(SetupWizard *wizard, QWidget *parent = 0); + ~OutputPage(); + bool validatePage(); + +private: + Ui::OutputPageFixedwing *ui; +}; + +#endif // OUTPUTPAGEFIXEDWING_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui new file mode 100644 index 000000000..bb7132888 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui @@ -0,0 +1,153 @@ + + + OutputPageFixedwing + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + <!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:12pt; font-weight:600;">OpenPilot 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-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 set an optimal configuration of the output signals powering your servos, the wizard needs to know what type of servos 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-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 one of the options below. If you are unsure about the capabilities of your servos, 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></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + true + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + + + + 10 + + + + Standard ESC 50Hz + + + QToolButton { border: none } + + + Standard Servos + + + + :/setupwizard/resources/bttn-ESC-up.png + :/setupwizard/resources/bttn-ESC-down.png:/setupwizard/resources/bttn-ESC-up.png + + + + 200 + 100 + + + + true + + + false + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + + + + + + 10 + + + + Turbo PWM ESC 400Hz + + + QToolButton { border: none } + + + Digital Servos + + + + :/setupwizard/resources/bttn-turbo-up.png + :/setupwizard/resources/bttn-turbo-down.png:/setupwizard/resources/bttn-turbo-up.png + + + + 200 + 100 + + + + true + + + true + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index eccfd2ce2..2ee8bf039 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -36,6 +36,7 @@ #include "pages/surfacepage.h" #include "pages/inputpage.h" #include "pages/outputpage.h" +#include "pages/outputpagefixedwing.h" #include "pages/biascalibrationpage.h" #include "pages/summarypage.h" #include "pages/savepage.h" @@ -113,7 +114,7 @@ int SetupWizard::nextId() const return PAGE_OUTPUT; case PAGE_FIXEDWING: - return PAGE_OUTPUT; + return PAGE_OUTPUT_FIXEDWING; case PAGE_INPUT: if (isRestartNeeded()) { @@ -128,6 +129,9 @@ int SetupWizard::nextId() const case PAGE_OUTPUT: return PAGE_SUMMARY; + case PAGE_OUTPUT_FIXEDWING: + return PAGE_SUMMARY; + case PAGE_BIAS_CALIBRATION: return PAGE_OUTPUT_CALIBRATION; @@ -319,6 +323,7 @@ void SetupWizard::createPages() setPage(PAGE_SURFACE, new SurfacePage(this)); setPage(PAGE_INPUT, new InputPage(this)); setPage(PAGE_OUTPUT, new OutputPage(this)); + setPage(PAGE_OUTPUT_FIXEDWING, new OutputPageFixedwing(this)); setPage(PAGE_BIAS_CALIBRATION, new BiasCalibrationPage(this)); // setPage(PAGE_REVO_CALIBRATION, new RevoCalibrationPage(this)); setPage(PAGE_OUTPUT_CALIBRATION, new OutputCalibrationPage(this)); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h index a908ac989..434856607 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -156,9 +156,10 @@ private slots: void pageChanged(int currId); private: enum { PAGE_START, PAGE_CONTROLLER, PAGE_VEHICLES, PAGE_MULTI, PAGE_FIXEDWING, - PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_OUTPUT, PAGE_BIAS_CALIBRATION, - PAGE_REVO_CALIBRATION, PAGE_OUTPUT_CALIBRATION, PAGE_SAVE, PAGE_SUMMARY, - PAGE_NOTYETIMPLEMENTED, PAGE_REBOOT, PAGE_END, PAGE_UPDATE }; + PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_OUTPUT, PAGE_OUTPUT_FIXEDWING, + PAGE_BIAS_CALIBRATION,PAGE_REVO_CALIBRATION, PAGE_OUTPUT_CALIBRATION, + PAGE_SAVE, PAGE_SUMMARY,PAGE_NOTYETIMPLEMENTED, PAGE_REBOOT, PAGE_END, + PAGE_UPDATE }; void createPages(); bool saveHardwareSettings() const; bool canAutoUpdate() const; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index 366b7eae9..51a98c880 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -23,6 +23,7 @@ HEADERS += setupwizardplugin.h \ pages/surfacepage.h \ pages/abstractwizardpage.h \ pages/outputpage.h \ + pages/outputpagefixedwing.h \ pages/inputpage.h \ pages/summarypage.h \ vehicleconfigurationsource.h \ @@ -50,6 +51,7 @@ SOURCES += setupwizardplugin.cpp \ pages/surfacepage.cpp \ pages/abstractwizardpage.cpp \ pages/outputpage.cpp \ + pages/outputpagefixedwing.cpp \ pages/inputpage.cpp \ pages/summarypage.cpp \ vehicleconfigurationsource.cpp \ @@ -77,6 +79,7 @@ FORMS += \ pages/helipage.ui \ pages/surfacepage.ui \ pages/outputpage.ui \ + pages/outputpagefixedwing.ui \ pages/inputpage.ui \ pages/summarypage.ui \ connectiondiagram.ui \ From ea1e95db7ba94b69136f5ab12f36d4f6c9fb1c4a Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 17 Aug 2014 22:55:11 +1000 Subject: [PATCH 043/203] Minor refactroring of a type in a class, change ESC_TYPE and geter / serter to be actuator type as we are dealing with servos. Add servos to enum, remove hard coded min / max for now. --- .../plugins/setupwizard/pages/outputpage.cpp | 4 +- .../setupwizard/pages/outputpagefixedwing.cpp | 6 +-- .../setupwizard/pages/outputpagefixedwing.h | 2 +- .../setupwizard/pages/outputpagefixedwing.ui | 2 +- .../src/plugins/setupwizard/setupwizard.cpp | 11 ++++- .../src/plugins/setupwizard/setupwizard.h | 6 +-- .../vehicleconfigurationhelper.cpp | 47 ++++++++++++++----- .../setupwizard/vehicleconfigurationhelper.h | 5 +- .../setupwizard/vehicleconfigurationsource.h | 4 +- 9 files changed, 59 insertions(+), 28 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.cpp index b57237f3f..b00c6cfa3 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.cpp @@ -45,9 +45,9 @@ OutputPage::~OutputPage() bool OutputPage::validatePage() { if (ui->rapidESCButton->isChecked()) { - getWizard()->setESCType(SetupWizard::ESC_RAPID); + getWizard()->setActuatorType(SetupWizard::ESC_RAPID); } else { - getWizard()->setESCType(SetupWizard::ESC_LEGACY); + getWizard()->setActuatorType(SetupWizard::ESC_LEGACY); } return true; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp index 66db90bdf..b635a5e55 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp @@ -44,10 +44,10 @@ OutputPageFixedwing::~OutputPageFixedwing() bool OutputPageFixedwing::validatePage() { - if (ui->rapidESCButton->isChecked()) { - getWizard()->setESCType(SetupWizard::ESC_RAPID); + if (ui->ServoTypeButton->isChecked()) { + getWizard()->setActuatorType(SetupWizard::SERVO_DIGITAL); } else { - getWizard()->setESCType(SetupWizard::ESC_LEGACY); + getWizard()->setActuatorType(SetupWizard::SERVO_LEGACY); } return true; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.h index d3d99b0fa..f3494b85b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.h @@ -39,7 +39,7 @@ class OutputPageFixedwing : public AbstractWizardPage { public: explicit OutputPageFixedwing(SetupWizard *wizard, QWidget *parent = 0); - ~OutputPage(); + ~OutputPageFixedwing(); bool validatePage(); private: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui index bb7132888..4d342ba47 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui @@ -99,7 +99,7 @@ p, li { white-space: pre-wrap; } - + 10 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 2ee8bf039..c40e0e253 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -291,14 +291,21 @@ QString SetupWizard::getSummaryText() } summary.append("
"); - summary.append("").append(tr("ESC type: ")).append(""); - switch (getESCType()) { + summary.append("").append(tr("Actuator type: ")).append(""); + switch (getActuatorType()) { case ESC_LEGACY: summary.append(tr("Legacy ESC (50 Hz)")); break; case ESC_RAPID: summary.append(tr("Rapid ESC (400 Hz)")); break; + case SERVO_LEGACY: + summary.append(tr("Legacy Servos (50 Hz)")); + break; + case SERVO_DIGITAL: + summary.append(tr("Digital Servos (333 Hz)")); + break; + default: summary.append(tr("Unknown")); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h index 434856607..c941561af 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -78,11 +78,11 @@ public: return m_inputType; } - void setESCType(SetupWizard::ESC_TYPE type) + void setActuatorType(SetupWizard::ACTUATOR_TYPE type) { m_escType = type; } - SetupWizard::ESC_TYPE getESCType() const + SetupWizard::ACTUATOR_TYPE getActuatorType() const { return m_escType; } @@ -168,7 +168,7 @@ private: VEHICLE_TYPE m_vehicleType; VEHICLE_SUB_TYPE m_vehicleSubType; INPUT_TYPE m_inputType; - ESC_TYPE m_escType; + ACTUATOR_TYPE m_escType; GPS_SETTING m_gpsSetting; RADIO_SETTING m_radioSetting; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 930d6e928..dbca5b044 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -42,6 +42,8 @@ const qint16 VehicleConfigurationHelper::LEGACY_ESC_FREQUENCE = 50; const qint16 VehicleConfigurationHelper::RAPID_ESC_FREQUENCE = 400; +const qint16 VehicleConfigurationHelper::LEGACY_SERVO_FREQUENCE = 50; +const qint16 VehicleConfigurationHelper::DIGITAL_SERVO_FREQUENCE = 333; VehicleConfigurationHelper::VehicleConfigurationHelper(VehicleConfigurationSource *configSource) : m_configSource(configSource), m_uavoManager(0), @@ -68,7 +70,7 @@ bool VehicleConfigurationHelper::setupVehicle(bool save) applyHardwareConfiguration(); applyVehicleConfiguration(); applyActuatorConfiguration(); - applyFlighModeConfiguration(); + applyFlightModeConfiguration(); if (save) { applySensorBiasConfiguration(); @@ -237,8 +239,10 @@ void VehicleConfigurationHelper::applyVehicleConfiguration() break; } case VehicleConfigurationSource::VEHICLE_HELI: + // TODO: Implement settings for Helis + break; case VehicleConfigurationSource::VEHICLE_SURFACE: - // TODO: Implement settings for other vehicle types? + // TODO: Implement settings for Surface break; default: break; @@ -270,7 +274,7 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() } qint16 updateFrequence = LEGACY_ESC_FREQUENCE; - switch (m_configSource->getESCType()) { + switch (m_configSource->getActuatorType()) { case VehicleConfigurationSource::ESC_LEGACY: updateFrequence = LEGACY_ESC_FREQUENCE; break; @@ -322,18 +326,31 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() { ActuatorSettings::DataFields data = actSettings->getData(); - qDebug() << "Override center, min and max pulses for fixed wing servos\n"; - // move all but first chan to 1500 center pluse QList actuatorSettings = m_configSource->getActuatorSettings(); for (quint16 i = 1; i < ActuatorSettings::CHANNELMAX_NUMELEM; i++) { data.ChannelType[i] = ActuatorSettings::CHANNELTYPE_PWM; data.ChannelAddr[i] = i; - data.ChannelMin[i] = 554; // Arduino library defaults to 554 http://arduino.cc/en/Reference/ServoAttach, - // 600 is for HS85mg - http://www.servocity.com/html/hs-85mg__mighty_micro.html#.U4JEWhapKBU - data.ChannelNeutral[i] = 1500; - data.ChannelMax[i] = 2400; // Same rules as above from the Arduino *generic* library and the servo city info for the 85mg + data.ChannelMin[i] = actuatorSettings[i].channelMin; + data.ChannelNeutral[i] = actuatorSettings[i].channelNeutral; + data.ChannelMax[i] = actuatorSettings[i].channelMax; } - qDebug() << "Save Fixed Wing Actuator Data\n"; + + for (quint16 i = 0; i < ActuatorSettings::CHANNELUPDATEFREQ_NUMELEM; i++) { + data.ChannelUpdateFreq[i] = LEGACY_SERVO_FREQUENCE; + } + + qint16 updateFrequence = LEGACY_SERVO_FREQUENCE; + switch (m_configSource->getActuatorType()) { + case VehicleConfigurationSource::SERVO_LEGACY: + updateFrequence = LEGACY_SERVO_FREQUENCE; + break; + case VehicleConfigurationSource::SERVO_DIGITAL: + updateFrequence = DIGITAL_SERVO_FREQUENCE; + break; + default: + break; + } + actSettings->setData(data); addModifiedObject(actSettings, tr("Writing actuator settings")); @@ -389,15 +406,19 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() } case VehicleConfigurationSource::VEHICLE_HELI: - case VehicleConfigurationSource::VEHICLE_SURFACE: - // TODO: Implement settings for other vehicle types? + // TODO: Implement settings for Heli vehicle types break; + + case VehicleConfigurationSource::VEHICLE_SURFACE: + // TODO: Implement settings for ground vehicle types + break; + default: break; } } -void VehicleConfigurationHelper::applyFlighModeConfiguration() +void VehicleConfigurationHelper::applyFlightModeConfiguration() { FlightModeSettings *modeSettings = FlightModeSettings::GetInstance(m_uavoManager); ManualControlSettings *controlSettings = ManualControlSettings::GetInstance(m_uavoManager); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h index 7829ac039..b2e525483 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h @@ -59,6 +59,9 @@ public: bool setupHardwareSettings(bool save = true); static const qint16 LEGACY_ESC_FREQUENCE; static const qint16 RAPID_ESC_FREQUENCE; + static const qint16 LEGACY_SERVO_FREQUENCE; + static const qint16 DIGITAL_SERVO_FREQUENCE; + signals: void saveProgress(int total, int current, QString description); @@ -79,7 +82,7 @@ private: void applyHardwareConfiguration(); void applyVehicleConfiguration(); void applyActuatorConfiguration(); - void applyFlighModeConfiguration(); + void applyFlightModeConfiguration(); void applySensorBiasConfiguration(); void applyStabilizationConfiguration(); void applyManualControlDefaults(); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 733518ee2..659da60fb 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -61,7 +61,7 @@ public: MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_X, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, MULTI_ROTOR_OCTO_X, MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, FIXED_WING_AILERON, FIXED_WING_VTAIL, FIXED_WING_ELEVON, HELI_CCPM }; - enum ESC_TYPE { ESC_RAPID, ESC_LEGACY, ESC_UNKNOWN }; + enum ACTUATOR_TYPE { ESC_RAPID, ESC_LEGACY, SERVO_LEGACY, SERVO_DIGITAL, ESC_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN }; enum GPS_SETTING { GPS_UBX, GPS_NMEA, GPS_DISABLED }; @@ -71,7 +71,7 @@ public: virtual VehicleConfigurationSource::VEHICLE_TYPE getVehicleType() const = 0; virtual VehicleConfigurationSource::VEHICLE_SUB_TYPE getVehicleSubType() const = 0; virtual VehicleConfigurationSource::INPUT_TYPE getInputType() const = 0; - virtual VehicleConfigurationSource::ESC_TYPE getESCType() const = 0; + virtual VehicleConfigurationSource::ACTUATOR_TYPE getActuatorType() const = 0; virtual VehicleConfigurationSource::GPS_SETTING getGPSSetting() const = 0; virtual VehicleConfigurationSource::RADIO_SETTING getRadioSetting() const = 0; From 2b6629e03a03043a54087756c57752b6fc0f2cbd Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 17 Aug 2014 23:06:01 +1000 Subject: [PATCH 044/203] Change wording, standard servos to analog servos --- .../src/plugins/setupwizard/pages/outputpagefixedwing.ui | 2 +- ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui index 4d342ba47..cf32527b4 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui @@ -68,7 +68,7 @@ p, li { white-space: pre-wrap; } QToolButton { border: none }
- Standard Servos + Analog Servos diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index c40e0e253..dd82b7cf5 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -300,7 +300,7 @@ QString SetupWizard::getSummaryText() summary.append(tr("Rapid ESC (400 Hz)")); break; case SERVO_LEGACY: - summary.append(tr("Legacy Servos (50 Hz)")); + summary.append(tr("Analog Servos (50 Hz)")); break; case SERVO_DIGITAL: summary.append(tr("Digital Servos (333 Hz)")); From a46d5316ec4a65e81c7930482d624420845e7a5c Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Mon, 18 Aug 2014 02:51:49 +1000 Subject: [PATCH 045/203] Tooltips --- .../src/plugins/setupwizard/pages/outputpagefixedwing.ui | 4 ++-- .../openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui index cf32527b4..fb8150ddf 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui @@ -62,7 +62,7 @@ p, li { white-space: pre-wrap; }
- Standard ESC 50Hz + Analog Servo 50Hz QToolButton { border: none } @@ -106,7 +106,7 @@ p, li { white-space: pre-wrap; } - Turbo PWM ESC 400Hz + Digital Servo 333Hz QToolButton { border: none } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui index b78313744..805659ebc 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui @@ -27,7 +27,7 @@ p, li { white-space: pre-wrap; } <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 and Fixed-wing aircraft.)</span></p></body></html> +<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 and Fixed-wing aircraft.</span></p></body></html> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop From 00ed28c98391dbc7776aad22453b4a89b5106c83 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Mon, 18 Aug 2014 03:43:00 +1000 Subject: [PATCH 046/203] Start adding PID page --- .../pages/airframestabfixedwing.cpp | 42 ++++++++++++++++ .../setupwizard/pages/airframestabfixedwing.h | 48 +++++++++++++++++++ .../pages/airframestabfixedwing.ui | 45 +++++++++++++++++ .../src/plugins/setupwizard/setupwizard.cpp | 16 +++++++ .../src/plugins/setupwizard/setupwizard.h | 4 +- .../src/plugins/setupwizard/setupwizard.pro | 9 ++-- 6 files changed, 159 insertions(+), 5 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.ui diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.cpp new file mode 100644 index 000000000..ae78d9254 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.cpp @@ -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 "airframestabfixedwing.h" +#include "ui_airframestabfixedwing.h" + +AirframeStabFixedwing::AirframeStabFixedwing(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::AirframeStabFixedwing) +{ + ui->setupUi(this); + setFinalPage(true); +} + +AirframeStabFixedwing::~AirframeStabFixedwing() +{ + delete ui; +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.h new file mode 100644 index 000000000..641927b7d --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.h @@ -0,0 +1,48 @@ +/** + ****************************************************************************** + * + * @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 AIRFRAMESTABFIXEDWING_H +#define AIRFRAMESTABFIXEDWING_H + +#include "abstractwizardpage.h" + +namespace Ui { +class AirframeStabFixedwing; +} + +class AirframeStabFixedwing : public AbstractWizardPage { + Q_OBJECT + +public: + explicit AirframeStabFixedwing(SetupWizard *wizard, QWidget *parent = 0); + ~AirframeStabFixedwing(); + +private: + Ui::AirframeStabFixedwing *ui; +}; + +#endif // AIRFRAMESTABFIXEDWING_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.ui new file mode 100644 index 000000000..582c76ef4 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.ui @@ -0,0 +1,45 @@ + + + AirframeStabFixedwing + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + 20 + 170 + 551 + 51 + + + + <!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;">TODO: This page handles PIDs, we get a choice of airframes, some generics as well as specifics like FPV Raptor and Funjet etc</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:12pt; font-weight:600;">Explain these are a starting point and likely will need further tuning as no two airframes are completely identical </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></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index dd82b7cf5..df335777a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -44,6 +44,7 @@ #include "pages/rebootpage.h" #include "pages/outputcalibrationpage.h" #include "pages/revocalibrationpage.h" +#include "pages/airframestabfixedwing.h" #include "extensionsystem/pluginmanager.h" #include "vehicleconfigurationhelper.h" #include "actuatorsettings.h" @@ -138,6 +139,20 @@ int SetupWizard::nextId() const // case PAGE_REVO_CALIBRATION: // return PAGE_OUTPUT_CALIBRATION; case PAGE_OUTPUT_CALIBRATION: + { + switch (getVehicleType()) { + case VEHICLE_FIXEDWING: + return PAGE_AIRFRAMESTAB_FIXEDWING; + //TODO: Pages for Multi and heli + case VEHICLE_MULTI: + case VEHICLE_HELI: + case VEHICLE_SURFACE: + case VEHICLE_UNKNOWN: + return PAGE_SAVE; + } + } + + case PAGE_AIRFRAMESTAB_FIXEDWING: return PAGE_SAVE; case PAGE_SUMMARY: @@ -338,6 +353,7 @@ void SetupWizard::createPages() setPage(PAGE_SAVE, new SavePage(this)); setPage(PAGE_REBOOT, new RebootPage(this)); setPage(PAGE_NOTYETIMPLEMENTED, new NotYetImplementedPage(this)); + setPage(PAGE_AIRFRAMESTAB_FIXEDWING, new AirframeStabFixedwing(this)); setPage(PAGE_END, new OPEndPage(this)); setStartId(PAGE_START); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h index c941561af..d914b994c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -158,8 +158,8 @@ private: enum { PAGE_START, PAGE_CONTROLLER, PAGE_VEHICLES, PAGE_MULTI, PAGE_FIXEDWING, PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_OUTPUT, PAGE_OUTPUT_FIXEDWING, PAGE_BIAS_CALIBRATION,PAGE_REVO_CALIBRATION, PAGE_OUTPUT_CALIBRATION, - PAGE_SAVE, PAGE_SUMMARY,PAGE_NOTYETIMPLEMENTED, PAGE_REBOOT, PAGE_END, - PAGE_UPDATE }; + PAGE_SAVE, PAGE_SUMMARY, PAGE_NOTYETIMPLEMENTED, PAGE_AIRFRAMESTAB_FIXEDWING, + PAGE_REBOOT, PAGE_END, PAGE_UPDATE }; void createPages(); bool saveHardwareSettings() const; bool canAutoUpdate() const; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index 51a98c880..9296cd5a7 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -36,7 +36,8 @@ HEADERS += setupwizardplugin.h \ pages/autoupdatepage.h \ pages/revocalibrationpage.h \ biascalibrationutil.h \ - pages/biascalibrationpage.h + pages/biascalibrationpage.h \ + pages/airframestabfixedwing.h SOURCES += setupwizardplugin.cpp \ setupwizard.cpp \ @@ -64,7 +65,8 @@ SOURCES += setupwizardplugin.cpp \ pages/autoupdatepage.cpp \ pages/revocalibrationpage.cpp \ biascalibrationutil.cpp \ - pages/biascalibrationpage.cpp + pages/biascalibrationpage.cpp \ + pages/airframestabfixedwing.cpp OTHER_FILES += SetupWizard.pluginspec @@ -88,7 +90,8 @@ FORMS += \ pages/savepage.ui \ pages/autoupdatepage.ui \ pages/revocalibrationpage.ui \ - pages/biascalibrationpage.ui + pages/biascalibrationpage.ui \ + pages/airframestabfixedwing.ui RESOURCES += \ wizardResources.qrc From 137a6e4308ce41af83228972f668c46737aec525 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Mon, 18 Aug 2014 03:47:16 +1000 Subject: [PATCH 047/203] Refactor name of legacy servos, remove PID hard coding from the config helper --- .../setupwizard/pages/outputpagefixedwing.cpp | 2 +- .../src/plugins/setupwizard/setupwizard.cpp | 2 +- .../vehicleconfigurationhelper.cpp | 54 ++----------------- .../setupwizard/vehicleconfigurationhelper.h | 2 +- .../setupwizard/vehicleconfigurationsource.h | 2 +- 5 files changed, 9 insertions(+), 53 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp index b635a5e55..6999877a7 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp @@ -47,7 +47,7 @@ bool OutputPageFixedwing::validatePage() if (ui->ServoTypeButton->isChecked()) { getWizard()->setActuatorType(SetupWizard::SERVO_DIGITAL); } else { - getWizard()->setActuatorType(SetupWizard::SERVO_LEGACY); + getWizard()->setActuatorType(SetupWizard::SERVO_ANALOG); } return true; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index df335777a..ec0903ed7 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -314,7 +314,7 @@ QString SetupWizard::getSummaryText() case ESC_RAPID: summary.append(tr("Rapid ESC (400 Hz)")); break; - case SERVO_LEGACY: + case SERVO_ANALOG: summary.append(tr("Analog Servos (50 Hz)")); break; case SERVO_DIGITAL: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index dbca5b044..489397736 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -42,7 +42,7 @@ const qint16 VehicleConfigurationHelper::LEGACY_ESC_FREQUENCE = 50; const qint16 VehicleConfigurationHelper::RAPID_ESC_FREQUENCE = 400; -const qint16 VehicleConfigurationHelper::LEGACY_SERVO_FREQUENCE = 50; +const qint16 VehicleConfigurationHelper::ANALOG_SERVO_FREQUENCE = 50; const qint16 VehicleConfigurationHelper::DIGITAL_SERVO_FREQUENCE = 333; VehicleConfigurationHelper::VehicleConfigurationHelper(VehicleConfigurationSource *configSource) @@ -336,13 +336,13 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() } for (quint16 i = 0; i < ActuatorSettings::CHANNELUPDATEFREQ_NUMELEM; i++) { - data.ChannelUpdateFreq[i] = LEGACY_SERVO_FREQUENCE; + data.ChannelUpdateFreq[i] = ANALOG_SERVO_FREQUENCE; } - qint16 updateFrequence = LEGACY_SERVO_FREQUENCE; + qint16 updateFrequence = ANALOG_SERVO_FREQUENCE; switch (m_configSource->getActuatorType()) { - case VehicleConfigurationSource::SERVO_LEGACY: - updateFrequence = LEGACY_SERVO_FREQUENCE; + case VehicleConfigurationSource::SERVO_ANALOG: + updateFrequence = ANALOG_SERVO_FREQUENCE; break; case VehicleConfigurationSource::SERVO_DIGITAL: updateFrequence = DIGITAL_SERVO_FREQUENCE; @@ -354,50 +354,6 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() actSettings->setData(data); addModifiedObject(actSettings, tr("Writing actuator settings")); - // I think I need to add a saved stabilizationsettings object also. - // unfortunately not sure this is the right way to do it! - - qDebug() << "Saving Fixed Wing Default PID Data\n"; - -/* - qDebug() << "Save Fixed Wing StabilizationBank object\n"; - StabilizationBank *stabilizationBank = StabilizationBank::GetInstance(m_uavoManager); - StabilizationBank::DataFields stabBank = stabilizationBank->getData(); - Values pulled from ./build/uavobject-synthetics/gcs/stabilizationbank.h - stabBank.PitchPI[StabilizationBank::PITCHPI_ILIMIT] = 1.123; - stabilizationBank->setData(stabBank); - addModifiedObject(stabilizationBank, tr("Writing stabilization bank")); -*/ - - qDebug() << "Save Fixed Wing StabilizationSettingsBank1 object\n"; - - // Values pulled from ./build/uavobject-synthetics/gcs/stabilizationsettingsbank1.h - StabilizationSettingsBank1 *stabilizationSettingsBank = StabilizationSettingsBank1::GetInstance(m_uavoManager); - StabilizationSettingsBank1::DataFields stabSettingsBank = stabilizationSettingsBank->getData(); - stabSettingsBank.RollRatePID[StabilizationSettingsBank1::ROLLRATEPID_KP] = 2.420; - stabSettingsBank.RollRatePID[StabilizationSettingsBank1::ROLLRATEPID_KI] = 2.420; - stabSettingsBank.RollPI[StabilizationSettingsBank1::ROLLPI_KP] = 2.420; - stabSettingsBank.RollPI[StabilizationSettingsBank1::ROLLPI_KI] = 2.420; - - stabSettingsBank.PitchRatePID[StabilizationSettingsBank1::PITCHRATEPID_KP] = 2.420; - stabSettingsBank.PitchRatePID[StabilizationSettingsBank1::PITCHRATEPID_KI] = 2.420; - stabSettingsBank.PitchPI[StabilizationSettingsBank1::PITCHPI_KP] = 2.420; - stabSettingsBank.PitchPI[StabilizationSettingsBank1::PITCHPI_KI] = 2.420; - - stabSettingsBank.YawRatePID[StabilizationSettingsBank1::YAWRATEPID_KP] = 2.420; - stabSettingsBank.YawRatePID[StabilizationSettingsBank1::YAWRATEPID_KI] = 2.420; - stabSettingsBank.YawPI[StabilizationSettingsBank1::YAWPI_KP] = 2.420; - stabSettingsBank.YawPI[StabilizationSettingsBank1::YAWPI_KI] = 2.420; - - - // need to set max servo throw via iLimit here per my notes in http://forums.openpilot.org/topic/32356-gonna-give-revo-a-run-on-my-bixler-v1-any-suggestions/#entry252556 - stabSettingsBank.PitchPI[StabilizationSettingsBank1::PITCHPI_ILIMIT] = 1.420; - stabSettingsBank.RollPI[StabilizationSettingsBank1::ROLLPI_ILIMIT] = 1.420; - stabSettingsBank.YawPI[StabilizationSettingsBank1::YAWPI_ILIMIT] = 1.420; - - stabilizationSettingsBank->setData(stabSettingsBank); - addModifiedObject(stabilizationSettingsBank, tr("Writing stabilization bank 1 settings")); - // Set up model view image here? // loop through all the window instances and check which are of the type ModelViewGadget. // per m_thread on each instance setAcFileName(QString model_file_name) and then call reloadScene() on the same object. diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h index b2e525483..91c244121 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h @@ -59,7 +59,7 @@ public: bool setupHardwareSettings(bool save = true); static const qint16 LEGACY_ESC_FREQUENCE; static const qint16 RAPID_ESC_FREQUENCE; - static const qint16 LEGACY_SERVO_FREQUENCE; + static const qint16 ANALOG_SERVO_FREQUENCE; static const qint16 DIGITAL_SERVO_FREQUENCE; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 659da60fb..375423b5b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -61,7 +61,7 @@ public: MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_X, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, MULTI_ROTOR_OCTO_X, MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, FIXED_WING_AILERON, FIXED_WING_VTAIL, FIXED_WING_ELEVON, HELI_CCPM }; - enum ACTUATOR_TYPE { ESC_RAPID, ESC_LEGACY, SERVO_LEGACY, SERVO_DIGITAL, ESC_UNKNOWN }; + enum ACTUATOR_TYPE { ESC_RAPID, ESC_LEGACY, SERVO_ANALOG, SERVO_DIGITAL, ESC_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN }; enum GPS_SETTING { GPS_UBX, GPS_NMEA, GPS_DISABLED }; From 53547239286128e92e17f3c6e31356098601d949 Mon Sep 17 00:00:00 2001 From: m_thread Date: Mon, 18 Aug 2014 01:20:31 +0200 Subject: [PATCH 048/203] OP-1222 Renamed some files. Fixed Wing wizard made only available on Revo Moved motor for fixed wing to channel 3 since channel 3 got its own timer. Fixed a crash in config plugin when selecting Fixed Wing. Added code in outputcalibration in Fixed Wing setup to set min and max values as well as neutral for servos. Added Controller type Nano. --- .../configfixedwingwidget.cpp | 60 +++++---- ...wing.cpp => airframestabfixedwingpage.cpp} | 14 +- ...ixedwing.h => airframestabfixedwingpage.h} | 20 +-- ...edwing.ui => airframestabfixedwingpage.ui} | 8 +- .../pages/outputcalibrationpage.cpp | 122 +++++++----------- .../setupwizard/pages/outputcalibrationpage.h | 1 + .../pages/outputcalibrationpage.ui | 44 +++---- ...efixedwing.cpp => outputfixedwingpage.cpp} | 15 +-- ...tpagefixedwing.h => outputfixedwingpage.h} | 18 +-- ...agefixedwing.ui => outputfixedwingpage.ui} | 4 +- .../plugins/setupwizard/pages/vehiclepage.cpp | 6 + .../plugins/setupwizard/pages/vehiclepage.h | 1 + .../src/plugins/setupwizard/setupwizard.cpp | 8 +- .../src/plugins/setupwizard/setupwizard.pro | 12 +- .../vehicleconfigurationhelper.cpp | 55 ++++---- .../setupwizard/vehicleconfigurationsource.h | 2 +- 16 files changed, 180 insertions(+), 210 deletions(-) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{airframestabfixedwing.cpp => airframestabfixedwingpage.cpp} (75%) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{airframestabfixedwing.h => airframestabfixedwingpage.h} (71%) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{airframestabfixedwing.ui => airframestabfixedwingpage.ui} (93%) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{outputpagefixedwing.cpp => outputfixedwingpage.cpp} (82%) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{outputpagefixedwing.h => outputfixedwingpage.h} (77%) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{outputpagefixedwing.ui => outputfixedwingpage.ui} (98%) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 2fc27cd51..47b8d050a 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -43,6 +43,33 @@ const QString ConfigFixedWingWidget::CHANNELBOXNAME = QString("fixedWingChannelBox"); +ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : + VehicleConfig(parent), m_aircraft(new Ui_FixedWingConfigWidget()), + plane(NULL) +{ + m_aircraft->setupUi(this); + + plane = new QGraphicsSvgItem(); + populateChannelComboBoxes(); + + QStringList fixedWingTypes; + fixedWingTypes << "Elevator aileron rudder" << "Elevon"; + m_aircraft->fixedWingType->addItems(fixedWingTypes); + + // Set default model to "Elevator aileron rudder" + m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); + + setupUI(m_aircraft->fixedWingType->currentText()); + + connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); + updateEnableControls(); +} + +ConfigFixedWingWidget::~ConfigFixedWingWidget() +{ + delete m_aircraft; +} + QStringList ConfigFixedWingWidget::getChannelDescriptions() { // init a channel_numelem list of channel desc defaults @@ -80,31 +107,6 @@ QStringList ConfigFixedWingWidget::getChannelDescriptions() return channelDesc; } -ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : - VehicleConfig(parent), m_aircraft(new Ui_FixedWingConfigWidget()) -{ - m_aircraft->setupUi(this); - - populateChannelComboBoxes(); - - QStringList fixedWingTypes; - fixedWingTypes << "Elevator aileron rudder" << "Elevon"; - m_aircraft->fixedWingType->addItems(fixedWingTypes); - - // Set default model to "Elevator aileron rudder" - m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); - - //setupUI(m_aircraft->fixedWingType->currentText()); - - connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); - updateEnableControls(); -} - -ConfigFixedWingWidget::~ConfigFixedWingWidget() -{ - delete m_aircraft; -} - void ConfigFixedWingWidget::setupUI(QString frameType) { Q_ASSERT(m_aircraft); @@ -633,15 +635,10 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) return error; } -/** - WHAT DOES THIS DO??? - */ void ConfigFixedWingWidget::showEvent(QShowEvent *event) { Q_UNUSED(event) - // Thit fitInView method should only be called now, once the - // widget is shown, otherwise it cannot compute its values and - // the result is usually a ahrsbargraph that is way too small. + Q_ASSERT(plane); m_aircraft->planeShape->fitInView(plane, Qt::KeepAspectRatio); } @@ -651,6 +648,7 @@ void ConfigFixedWingWidget::showEvent(QShowEvent *event) void ConfigFixedWingWidget::resizeEvent(QResizeEvent *event) { Q_UNUSED(event); + Q_ASSERT(plane); m_aircraft->planeShape->fitInView(plane, Qt::KeepAspectRatio); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.cpp similarity index 75% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.cpp rename to ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.cpp index ae78d9254..c2d5eebaf 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.cpp @@ -1,11 +1,11 @@ /** ****************************************************************************** * - * @file notyetimplementedpage.cpp + * @file airframestabfixedwingpage.cpp * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup * @{ - * @addtogroup NotYetImplementedPage + * @addtogroup AirframeStabFixedwingPage * @{ * @brief *****************************************************************************/ @@ -25,18 +25,18 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "airframestabfixedwing.h" -#include "ui_airframestabfixedwing.h" +#include "airframestabfixedwingpage.h" +#include "ui_airframestabfixedwingpage.h" -AirframeStabFixedwing::AirframeStabFixedwing(SetupWizard *wizard, QWidget *parent) : +AirframeStabFixedwingPage::AirframeStabFixedwingPage(SetupWizard *wizard, QWidget *parent) : AbstractWizardPage(wizard, parent), - ui(new Ui::AirframeStabFixedwing) + ui(new Ui::AirframeStabFixedwingPage) { ui->setupUi(this); setFinalPage(true); } -AirframeStabFixedwing::~AirframeStabFixedwing() +AirframeStabFixedwingPage::~AirframeStabFixedwingPage() { delete ui; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.h similarity index 71% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.h rename to ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.h index 641927b7d..4a6dae8dc 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.h @@ -1,11 +1,11 @@ /** ****************************************************************************** * - * @file notyetimplementedpage.h + * @file airframestabfixedwingpage.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup * @{ - * @addtogroup NotYetImplementedPage + * @addtogroup AirframeStabFixedwingPage * @{ * @brief *****************************************************************************/ @@ -25,24 +25,24 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef AIRFRAMESTABFIXEDWING_H -#define AIRFRAMESTABFIXEDWING_H +#ifndef AIRFRAMESTABFIXEDWINGPAGE_H +#define AIRFRAMESTABFIXEDWINGPAGE_H #include "abstractwizardpage.h" namespace Ui { -class AirframeStabFixedwing; +class AirframeStabFixedwingPage; } -class AirframeStabFixedwing : public AbstractWizardPage { +class AirframeStabFixedwingPage : public AbstractWizardPage { Q_OBJECT public: - explicit AirframeStabFixedwing(SetupWizard *wizard, QWidget *parent = 0); - ~AirframeStabFixedwing(); + explicit AirframeStabFixedwingPage(SetupWizard *wizard, QWidget *parent = 0); + ~AirframeStabFixedwingPage(); private: - Ui::AirframeStabFixedwing *ui; + Ui::AirframeStabFixedwingPage *ui; }; -#endif // AIRFRAMESTABFIXEDWING_H +#endif // AIRFRAMESTABFIXEDWINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.ui similarity index 93% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.ui rename to ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.ui index 582c76ef4..31e672b1f 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwing.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.ui @@ -1,7 +1,7 @@ - AirframeStabFixedwing - + AirframeStabFixedwingPage + 0 @@ -17,9 +17,9 @@ 20 - 170 + 130 551 - 51 + 191 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index d724f6076..4d9c74930 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -64,6 +64,33 @@ void OutputCalibrationPage::loadSVGFile(QString file) } } +void OutputCalibrationPage::setupActuatorMinMaxAndNeutral(int motorChannelStart, int motorChannelEnd, int totalUsedChannels) +{ + // Default values for the actuator settings, extra important for + // servos since a value out of range can actually destroy the + // vehicle if unlucky. + // Motors are not that important. REMOVE propellers always!! + + for (int servoid = 0; servoid < 12; servoid++) { + if (servoid >= motorChannelStart && servoid <= motorChannelEnd) { + // Set to motor safe values + m_actuatorSettings[servoid].channelMin = 1000; + m_actuatorSettings[servoid].channelNeutral = 1000; + m_actuatorSettings[servoid].channelMax = 2000; + } else if (servoid < totalUsedChannels) { + // Set to servo safe values + m_actuatorSettings[servoid].channelMin = 1500; + m_actuatorSettings[servoid].channelNeutral = 1500; + m_actuatorSettings[servoid].channelMax = 1500; + } else { + // "Disable" these channels + m_actuatorSettings[servoid].channelMin = 1000; + m_actuatorSettings[servoid].channelNeutral = 1000; + m_actuatorSettings[servoid].channelMax = 1000; + } + } +} + void OutputCalibrationPage::setupVehicle() { m_actuatorSettings = getWizard()->getActuatorSettings(); @@ -93,13 +120,8 @@ void OutputCalibrationPage::setupVehicle() // The channel number to configure for each step. m_channelIndex << 0 << 0 << 1 << 2 << 3 << 3 << 3; - // Default values for the actuator settings, extra important for - // servos since a value out of range can actually destroy the - // vehicle if unlucky. - // Motors are not that important. REMOVE propellers always!! - m_actuatorSettings[3].channelMin = 1500; - m_actuatorSettings[3].channelNeutral = 1500; - m_actuatorSettings[3].channelMax = 1500; + setupActuatorMinMaxAndNeutral(0, 1, 3); + getWizard()->setActuatorSettings(m_actuatorSettings); break; case SetupWizard::MULTI_ROTOR_QUAD_X: @@ -108,6 +130,7 @@ void OutputCalibrationPage::setupVehicle() 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; + setupActuatorMinMaxAndNeutral(0, 3, 4); break; case SetupWizard::MULTI_ROTOR_QUAD_PLUS: loadSVGFile(MULTI_SVG_FILE); @@ -115,6 +138,7 @@ void OutputCalibrationPage::setupVehicle() 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; + setupActuatorMinMaxAndNeutral(0, 3, 4); break; case SetupWizard::MULTI_ROTOR_HEXA: loadSVGFile(MULTI_SVG_FILE); @@ -122,6 +146,7 @@ void OutputCalibrationPage::setupVehicle() 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; + setupActuatorMinMaxAndNeutral(0, 5, 6); break; case SetupWizard::MULTI_ROTOR_HEXA_COAX_Y: loadSVGFile(MULTI_SVG_FILE); @@ -129,6 +154,7 @@ void OutputCalibrationPage::setupVehicle() 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; + setupActuatorMinMaxAndNeutral(0, 5, 6); break; case SetupWizard::MULTI_ROTOR_HEXA_H: loadSVGFile(MULTI_SVG_FILE); @@ -136,92 +162,35 @@ void OutputCalibrationPage::setupVehicle() 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; + setupActuatorMinMaxAndNeutral(0, 5, 6); break; case SetupWizard::MULTI_ROTOR_HEXA_X: m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; m_vehicleElementIds << "hexa-x" << "hexa-x-frame" << "hexa-x-m1" << "hexa-x-m2" << "hexa-x-m3" << "hexa-x-m4" << "hexa-x-m5" << "hexa-x-m6"; m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6; m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4 << 5; + setupActuatorMinMaxAndNeutral(0, 5, 6); break; // Fixed Wing case SetupWizard::FIXED_WING_AILERON: loadSVGFile(FIXEDWING_SVG_FILE); - m_wizardIndexes << 0 << 1 << 2 << 2 << 2 << 2; //2 for servoCenterSlider! + m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4; m_vehicleElementIds << "aileron" << "aileron-frame" << "aileron-motor" << "aileron-ail-left" << "aileron-ail-right" << "aileron-rudder" << "aileron-elevator"; - m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5; - m_channelIndex << 0 << 0 << 1 << 2 << 3 << 4; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3 << 4 << 4 << 4 << 5 << 5 << 5; + m_channelIndex << 0 << 3 << 0 << 0 << 0 << 1 << 1 << 1 << 2 << 2 << 2 << 4 << 4 << 4; - // see Servo city for an example. 1500 usec is center on MS85mg for example. - // - http://www.servocity.com/html/hs-85mg__mighty_micro.html - // make sure Aileron servo one does not go to an extreme value - // would also be nice to make these all default to 50hz so we don't shred servos. - - m_actuatorSettings[1].channelNeutral = 1500; - // make sure Aileron servo two does not go to an extreme value - m_actuatorSettings[2].channelNeutral = 1500; - // make sure Elevator servo one does not go to an extreme value - m_actuatorSettings[3].channelNeutral = 1500; - // make sure Rudder servo one does not go to an extreme value - m_actuatorSettings[4].channelNeutral = 1500; - m_actuatorSettings[4].channelNeutral = 1500; - m_actuatorSettings[5].channelNeutral = 1500; - m_actuatorSettings[6].channelNeutral = 1500; - m_actuatorSettings[7].channelNeutral = 1500; - - // Arduino library defaults to 554 http://arduino.cc/en/Reference/ServoAttach, - // 600 is for HS85mg - http://www.servocity.com/html/hs-85mg__mighty_micro.html#.U4JEWhapKBU - // Same rules as above from the Arduino *generic* library and the servo city info for the 85mg - m_actuatorSettings[1].channelMin = 554; - m_actuatorSettings[1].channelMax = 2400; - m_actuatorSettings[2].channelMin = 554; - m_actuatorSettings[2].channelMax = 2400; - m_actuatorSettings[3].channelMin = 554; - m_actuatorSettings[3].channelMax = 2400; - m_actuatorSettings[4].channelMin = 554; - m_actuatorSettings[4].channelMax = 2400; - m_actuatorSettings[5].channelMin = 554; - m_actuatorSettings[5].channelMax = 2400; - m_actuatorSettings[6].channelMin = 554; - m_actuatorSettings[6].channelMax = 2400; - m_actuatorSettings[7].channelMin = 554; - m_actuatorSettings[7].channelMax = 2400; + setupActuatorMinMaxAndNeutral(3, 3, 5); getWizard()->setActuatorSettings(m_actuatorSettings); break; case SetupWizard::FIXED_WING_ELEVON: loadSVGFile(FIXEDWING_SVG_FILE); - m_wizardIndexes << 0 << 1 << 2 << 2; //2 for servoCenterSlider! + m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4; m_vehicleElementIds << "elevon" << "elevon-frame" << "elevon-motor" << "elevon-left" << "elevon-right"; - m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3; - m_channelIndex << 0 << 0 << 1 << 2; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3; + m_channelIndex << 0 << 3 << 0 << 0 << 0 << 1 << 1 << 1; - // make sure elevon servo one does not go to an extreme value - m_actuatorSettings[1].channelNeutral = 1500; - // make sure elevon servo two does not go to an extreme value - m_actuatorSettings[2].channelNeutral = 1500; - m_actuatorSettings[3].channelNeutral = 1500; - m_actuatorSettings[4].channelNeutral = 1500; - m_actuatorSettings[5].channelNeutral = 1500; - m_actuatorSettings[6].channelNeutral = 1500; - m_actuatorSettings[7].channelNeutral = 1500; - - // Arduino library defaults to 554 http://arduino.cc/en/Reference/ServoAttach, - // 600 is for HS85mg - http://www.servocity.com/html/hs-85mg__mighty_micro.html#.U4JEWhapKBU - // Same rules as above from the Arduino *generic* library and the servo city info for the 85mg - m_actuatorSettings[1].channelMin = 554; - m_actuatorSettings[1].channelMax = 2400; - m_actuatorSettings[2].channelMin = 554; - m_actuatorSettings[2].channelMax = 2400; - m_actuatorSettings[3].channelMin = 554; - m_actuatorSettings[3].channelMax = 2400; - m_actuatorSettings[4].channelMin = 554; - m_actuatorSettings[4].channelMax = 2400; - m_actuatorSettings[5].channelMin = 554; - m_actuatorSettings[5].channelMax = 2400; - m_actuatorSettings[6].channelMin = 554; - m_actuatorSettings[6].channelMax = 2400; - m_actuatorSettings[7].channelMin = 554; - m_actuatorSettings[7].channelMax = 2400; + setupActuatorMinMaxAndNeutral(3, 3, 3); getWizard()->setActuatorSettings(m_actuatorSettings); break; @@ -298,7 +267,7 @@ void OutputCalibrationPage::setWizardPage() ui->calibrationStack->setCurrentIndex(currentPageIndex); int currentChannel = getCurrentChannel(); - qDebug() << "Current channel: " << currentChannel+1; + qDebug() << "Current channel: " << currentChannel + 1; if (currentChannel >= 0) { if (currentPageIndex == 1) { ui->motorNeutralSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral); @@ -381,7 +350,8 @@ 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); + quint16 safeValue = m_actuatorSettings[channel].channelNeutral; + onStartButtonToggle(ui->motorNeutralButton, channel, m_actuatorSettings[channel].channelNeutral, safeValue, ui->motorNeutralSlider); } void OutputCalibrationPage::onStartButtonToggle(QAbstractButton *button, quint16 channel, quint16 value, quint16 safeValue, QSlider *slider) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.h index 0ad5f428f..d851fa639 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.h @@ -53,6 +53,7 @@ public: } void loadSVGFile(QString file); + void setupActuatorMinMaxAndNeutral(int motorChannelStart, int motorChannelEnd, int totalUsedChannels); protected: void showEvent(QShowEvent *event); void resizeEvent(QResizeEvent *event); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui index f80cab6de..e69c67666 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui @@ -34,7 +34,7 @@ - 1 + 4 @@ -72,7 +72,7 @@ p, li { white-space: pre-wrap; } - <html><head/><body><p>In this step we will set the neutral rate for the motor highlighted in the illustration to the right. <br/>Please pay attention to the details and in particular the motors position and its rotation direction. Ensure the motors are spinning in the correct direction as shown in the diagram. Swap any 2 motor wires to change the direction of a motor. </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 stable. <br/><br/>When done press button again to stop.</p></body></html> + <html><head/><body><p>In this step we will set the neutral rate for the motor highlighted in the illustration to the right. <br/>Please pay attention to the details and in particular the motors position and its rotation direction. Ensure the motors are spinning in the correct direction as shown in the diagram. Swap any 2 motor wires to change the direction of a motor. </p><p>To find <span style=" font-weight:600;">the neutral rate for this engine</span>, press the Start button below and slide the slider to the right until the engine just starts to spin stable. <br/><br/>When done press button again to stop.</p></body></html> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop @@ -91,13 +91,13 @@ p, li { white-space: pre-wrap; } 1000 - 1300 + 1500 - 10 + 1 - 20 + 10 Qt::Horizontal @@ -133,7 +133,7 @@ p, li { white-space: pre-wrap; } - <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> + <html><head/><body><p>This step calibrates<span style=" font-weight:600;"> the center position of the servo</span>. 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> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop @@ -149,16 +149,16 @@ p, li { white-space: pre-wrap; } false - 1000 + 600 - 2000 + 2400 - 10 + 1 - 20 + 10 1500 @@ -198,12 +198,12 @@ p, li { white-space: pre-wrap; } - + - <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> + <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 <span style=" font-weight:600;">the minimum angle for the servo</span>, 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> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop @@ -219,16 +219,16 @@ p, li { white-space: pre-wrap; } false - 1000 + 600 - 1500 + 2400 - 10 + 1 - 20 + 10 1500 @@ -268,12 +268,12 @@ p, li { white-space: pre-wrap; } - + - <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> + <html><head/><body><p>To set <span style=" font-weight:600;">the maximum angle for the servo</span>, 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> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop @@ -289,16 +289,16 @@ p, li { white-space: pre-wrap; } false - 1500 + 600 - 2000 + 2400 - 10 + 1 - 20 + 10 1500 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.cpp similarity index 82% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp rename to ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.cpp index 6999877a7..2977e9606 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.cpp @@ -1,7 +1,7 @@ /** ****************************************************************************** * - * @file outputpage.cpp + * @file outputfixedwingpage.cpp * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup * @{ @@ -25,24 +25,23 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "outputpagefixedwing.h" -#include "ui_outputpagefixedwing.h" +#include "outputfixedwingpage.h" +#include "ui_outputfixedwingpage.h" #include "setupwizard.h" -OutputPageFixedwing::OutputPageFixedwing(SetupWizard *wizard, QWidget *parent) : +OutputFixedwingPage::OutputFixedwingPage(SetupWizard *wizard, QWidget *parent) : AbstractWizardPage(wizard, parent), - - ui(new Ui::OutputPageFixedwing) + ui(new Ui::OutputFixedwingPage) { ui->setupUi(this); } -OutputPageFixedwing::~OutputPageFixedwing() +OutputFixedwingPage::~OutputFixedwingPage() { delete ui; } -bool OutputPageFixedwing::validatePage() +bool OutputFixedwingPage::validatePage() { if (ui->ServoTypeButton->isChecked()) { getWizard()->setActuatorType(SetupWizard::SERVO_DIGITAL); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.h similarity index 77% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.h rename to ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.h index f3494b85b..b68dd4fbc 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.h @@ -1,7 +1,7 @@ /** ****************************************************************************** * - * @file outputpage.h + * @file outputfixedwingpage.h * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup * @{ @@ -25,25 +25,25 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef OUTPUTPAGEFIXEDWING_H -#define OUTPUTPAGEFIXEDWING_H +#ifndef OUTPUTFIXEDWINGPAGE_H +#define OUTPUTFIXEDWINGPAGE_H #include "abstractwizardpage.h" namespace Ui { -class OutputPageFixedwing; +class OutputFixedwingPage; } -class OutputPageFixedwing : public AbstractWizardPage { +class OutputFixedwingPage : public AbstractWizardPage { Q_OBJECT public: - explicit OutputPageFixedwing(SetupWizard *wizard, QWidget *parent = 0); - ~OutputPageFixedwing(); + explicit OutputFixedwingPage(SetupWizard *wizard, QWidget *parent = 0); + ~OutputFixedwingPage(); bool validatePage(); private: - Ui::OutputPageFixedwing *ui; + Ui::OutputFixedwingPage *ui; }; -#endif // OUTPUTPAGEFIXEDWING_H +#endif // OUTPUTFIXEDWINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.ui similarity index 98% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui rename to ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.ui index fb8150ddf..ace236fce 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpagefixedwing.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.ui @@ -1,7 +1,7 @@ - OutputPageFixedwing - + OutputFixedwingPage + 0 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp index b7de92bc9..a8b1780a9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp @@ -55,3 +55,9 @@ bool VehiclePage::validatePage() } return true; } + +void VehiclePage::initializePage() +{ + ui->fixedwingButton->setEnabled(getWizard()->getControllerType() == SetupWizard::CONTROLLER_REVO || + getWizard()->getControllerType() == SetupWizard::CONTROLLER_NANO); +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h index 737f1fc25..659ac74cd 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.h @@ -41,6 +41,7 @@ public: explicit VehiclePage(SetupWizard *wizard, QWidget *parent = 0); ~VehiclePage(); bool validatePage(); + void initializePage(); private: Ui::VehiclePage *ui; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index ec0903ed7..65e12f2ff 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -36,7 +36,7 @@ #include "pages/surfacepage.h" #include "pages/inputpage.h" #include "pages/outputpage.h" -#include "pages/outputpagefixedwing.h" +#include "pages/outputfixedwingpage.h" #include "pages/biascalibrationpage.h" #include "pages/summarypage.h" #include "pages/savepage.h" @@ -44,7 +44,7 @@ #include "pages/rebootpage.h" #include "pages/outputcalibrationpage.h" #include "pages/revocalibrationpage.h" -#include "pages/airframestabfixedwing.h" +#include "pages/airframestabfixedwingpage.h" #include "extensionsystem/pluginmanager.h" #include "vehicleconfigurationhelper.h" #include "actuatorsettings.h" @@ -345,7 +345,7 @@ void SetupWizard::createPages() setPage(PAGE_SURFACE, new SurfacePage(this)); setPage(PAGE_INPUT, new InputPage(this)); setPage(PAGE_OUTPUT, new OutputPage(this)); - setPage(PAGE_OUTPUT_FIXEDWING, new OutputPageFixedwing(this)); + setPage(PAGE_OUTPUT_FIXEDWING, new OutputFixedwingPage(this)); setPage(PAGE_BIAS_CALIBRATION, new BiasCalibrationPage(this)); // setPage(PAGE_REVO_CALIBRATION, new RevoCalibrationPage(this)); setPage(PAGE_OUTPUT_CALIBRATION, new OutputCalibrationPage(this)); @@ -353,7 +353,7 @@ void SetupWizard::createPages() setPage(PAGE_SAVE, new SavePage(this)); setPage(PAGE_REBOOT, new RebootPage(this)); setPage(PAGE_NOTYETIMPLEMENTED, new NotYetImplementedPage(this)); - setPage(PAGE_AIRFRAMESTAB_FIXEDWING, new AirframeStabFixedwing(this)); + setPage(PAGE_AIRFRAMESTAB_FIXEDWING, new AirframeStabFixedwingPage(this)); setPage(PAGE_END, new OPEndPage(this)); setStartId(PAGE_START); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index 9296cd5a7..e6b32a913 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -23,7 +23,6 @@ HEADERS += setupwizardplugin.h \ pages/surfacepage.h \ pages/abstractwizardpage.h \ pages/outputpage.h \ - pages/outputpagefixedwing.h \ pages/inputpage.h \ pages/summarypage.h \ vehicleconfigurationsource.h \ @@ -37,7 +36,8 @@ HEADERS += setupwizardplugin.h \ pages/revocalibrationpage.h \ biascalibrationutil.h \ pages/biascalibrationpage.h \ - pages/airframestabfixedwing.h + pages/outputfixedwingpage.h \ + pages/airframestabfixedwingpage.h SOURCES += setupwizardplugin.cpp \ setupwizard.cpp \ @@ -52,7 +52,6 @@ SOURCES += setupwizardplugin.cpp \ pages/surfacepage.cpp \ pages/abstractwizardpage.cpp \ pages/outputpage.cpp \ - pages/outputpagefixedwing.cpp \ pages/inputpage.cpp \ pages/summarypage.cpp \ vehicleconfigurationsource.cpp \ @@ -66,7 +65,8 @@ SOURCES += setupwizardplugin.cpp \ pages/revocalibrationpage.cpp \ biascalibrationutil.cpp \ pages/biascalibrationpage.cpp \ - pages/airframestabfixedwing.cpp + pages/outputfixedwingpage.cpp \ + pages/airframestabfixedwingpage.cpp OTHER_FILES += SetupWizard.pluginspec @@ -81,7 +81,6 @@ FORMS += \ pages/helipage.ui \ pages/surfacepage.ui \ pages/outputpage.ui \ - pages/outputpagefixedwing.ui \ pages/inputpage.ui \ pages/summarypage.ui \ connectiondiagram.ui \ @@ -91,7 +90,8 @@ FORMS += \ pages/autoupdatepage.ui \ pages/revocalibrationpage.ui \ pages/biascalibrationpage.ui \ - pages/airframestabfixedwing.ui + pages/outputfixedwingpage.ui \ + pages/airframestabfixedwingpage.ui RESOURCES += \ wizardResources.qrc diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 489397736..9bd98c1df 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -231,7 +231,7 @@ void VehicleConfigurationHelper::applyVehicleConfiguration() setupElevon(); break; case VehicleConfigurationSource::FIXED_WING_VTAIL: -// setupVtail(); + // TODO: Implement settings for VTail fixed wings break; default: break; @@ -327,7 +327,7 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() ActuatorSettings::DataFields data = actSettings->getData(); QList actuatorSettings = m_configSource->getActuatorSettings(); - for (quint16 i = 1; i < ActuatorSettings::CHANNELMAX_NUMELEM; i++) { + for (quint16 i = 0; i < ActuatorSettings::CHANNELMAX_NUMELEM; i++) { data.ChannelType[i] = ActuatorSettings::CHANNELTYPE_PWM; data.ChannelAddr[i] = i; data.ChannelMin[i] = actuatorSettings[i].channelMin; @@ -335,10 +335,6 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() data.ChannelMax[i] = actuatorSettings[i].channelMax; } - for (quint16 i = 0; i < ActuatorSettings::CHANNELUPDATEFREQ_NUMELEM; i++) { - data.ChannelUpdateFreq[i] = ANALOG_SERVO_FREQUENCE; - } - qint16 updateFrequence = ANALOG_SERVO_FREQUENCE; switch (m_configSource->getActuatorType()) { case VehicleConfigurationSource::SERVO_ANALOG: @@ -351,6 +347,19 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() break; } + for (quint16 i = 0; i < ActuatorSettings::CHANNELUPDATEFREQ_NUMELEM; i++) { + if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) { + if (i == 1) { + data.ChannelUpdateFreq[i] = ANALOG_SERVO_FREQUENCE; + } + } else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { + if (i == 2) { + data.ChannelUpdateFreq[i] = ANALOG_SERVO_FREQUENCE; + } + } + data.ChannelUpdateFreq[i] = updateFrequence; + } + actSettings->setData(data); addModifiedObject(actSettings, tr("Writing actuator settings")); @@ -1549,31 +1558,17 @@ void VehicleConfigurationHelper::setupElevon() channels[1].type = MIXER_TYPE_SERVO; channels[1].throttle1 = 0; channels[1].throttle2 = 0; - channels[1].roll = -127; - channels[1].pitch = 127; + channels[1].roll = -100; + channels[1].pitch = 100; channels[1].yaw = 0; channels[2].type = MIXER_TYPE_SERVO; channels[2].throttle1 = 0; channels[2].throttle2 = 0; - channels[2].roll = 127; - channels[2].pitch = -127; + channels[2].roll = 100; + channels[2].pitch = -100; channels[2].yaw = 0; - channels[3].type = MIXER_TYPE_SERVO; - channels[3].throttle1 = 0; - channels[3].throttle2 = 0; - channels[3].roll = 0; - channels[3].pitch = 0; - channels[3].yaw = 0; - - channels[3].type = MIXER_TYPE_SERVO; - channels[3].throttle1 = 0; - channels[3].throttle2 = 0; - channels[3].roll = 0; - channels[3].pitch = 0; - channels[3].yaw = 0; - guiSettings.fixedwing.FixedWingThrottle = 1; guiSettings.fixedwing.FixedWingRoll1 = 2; guiSettings.fixedwing.FixedWingRoll2 = 3; @@ -1620,12 +1615,12 @@ void VehicleConfigurationHelper::setupAileron() channels[3].pitch = 100; channels[3].yaw = 0; - channels[3].type = MIXER_TYPE_SERVO; - channels[3].throttle1 = 0; - channels[3].throttle2 = 0; - channels[3].roll = 0; - channels[3].pitch = 0; - channels[3].yaw = 100; + channels[4].type = MIXER_TYPE_SERVO; + channels[4].throttle1 = 0; + channels[4].throttle2 = 0; + channels[4].roll = 0; + channels[4].pitch = 0; + channels[4].yaw = 100; guiSettings.fixedwing.FixedWingThrottle = 1; guiSettings.fixedwing.FixedWingRoll1 = 2; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 375423b5b..d03a75356 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -55,7 +55,7 @@ class VehicleConfigurationSource { public: VehicleConfigurationSource(); - enum CONTROLLER_TYPE { CONTROLLER_UNKNOWN, CONTROLLER_CC, CONTROLLER_CC3D, CONTROLLER_REVO, CONTROLLER_OPLINK }; + enum CONTROLLER_TYPE { CONTROLLER_UNKNOWN, CONTROLLER_CC, CONTROLLER_CC3D, CONTROLLER_REVO, CONTROLLER_NANO, CONTROLLER_OPLINK }; enum VEHICLE_TYPE { VEHICLE_UNKNOWN, VEHICLE_MULTI, VEHICLE_FIXEDWING, VEHICLE_HELI, VEHICLE_SURFACE }; enum VEHICLE_SUB_TYPE { MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS, MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_X, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, From 82a3590da53f1f3afd73bf5f6219509e579aa455 Mon Sep 17 00:00:00 2001 From: m_thread Date: Mon, 18 Aug 2014 13:14:07 +0200 Subject: [PATCH 049/203] OP-1222 Fixed a bug with Actuator settings and banks to use for motors. --- .../src/plugins/coreplugin/core.qrc | 1 + .../plugins/coreplugin/images/opie_90x120.gif | Bin 0 -> 358370 bytes .../plugins/coreplugin/qml/AboutDialog.qml | 21 +++++++++++++++++- .../vehicleconfigurationhelper.cpp | 2 +- 4 files changed, 22 insertions(+), 2 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/coreplugin/images/opie_90x120.gif diff --git a/ground/openpilotgcs/src/plugins/coreplugin/core.qrc b/ground/openpilotgcs/src/plugins/coreplugin/core.qrc index 61d0155d8..f850c7aee 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/core.qrc +++ b/ground/openpilotgcs/src/plugins/coreplugin/core.qrc @@ -63,5 +63,6 @@ qml/images/tab.png qml/AboutDialog.qml ../../../../../build/openpilotgcs-synthetics/AuthorsModel.qml + images/opie_90x120.gif diff --git a/ground/openpilotgcs/src/plugins/coreplugin/images/opie_90x120.gif b/ground/openpilotgcs/src/plugins/coreplugin/images/opie_90x120.gif new file mode 100644 index 0000000000000000000000000000000000000000..417e4c032eb1bc89eedc79923c26747d144772a8 GIT binary patch literal 358370 zcmeF)S5VW7-|zchdVw@*qy_>~1Pr|j30*)8MWx9KMMVV-MJa+LbdVB26csTPrHB}$ zh>9ADfQlLr6~Ph^1nUZlE=?8)WZHa=)RWM*cz$52g6YvT~xEX{-1kYKoU&GmkYp`V}M zYP;LW$VlE1k2ouG_YqxDgVT>@m%d}BH9NEw6ck>)dL_uP9LcguOH2FfufO&?D002E za-GP%(d4$aws>c`mxVUBqqXWnRXSoU#5diS?(hHl;K+#+Cmy9+ByJ&psB*Y{Nd5P1 z-|DKWl@BG$t*$l6p0}cnZf2O7D-y0BP#ejzte|g9@gaA0b$z|)_^T)Abb$8tGa=K{ z)1T`d%XTSVxpGCkaHf*3^5lUqDo^cr^S^(E+!_a6J!g_v7c)kuI)AW zHCvps%OsDk@MoRla@*DkuGiBXD+77_pUvB5D`~rJ6>c6eKWwHpmT#Tzq0@AjGMa7G zl593t>oAsQJ&hnKEzk9RjVH&T6;Ydyo;Ey%E9QgxT-O2<#w^mKPO?NNP_ZZ=Z1rD%`N+3g#} z%O6ACY{c^~3&ZUM>6SGSn^!-T^7fHV1{!o7)>v$H&!X#2Jz)K@dBf9Oo5h);7bmP! zsp`X-mIKE&4`*83ic%lWvP^N(jtt+j-2l78h;WxlF5ay@kZd-ZW4YAgT2U0d-P7~v zAC{SJ8-M-!wfbwZn`LgMvGMf~YwX2~mDa7L#l>MecJ8;*UE(?YxJ>=l=(PNvv)JNV z>7^CAS?y`I6#xKYu~u!RX_e5Xsc=g$)_>sgIBGcMA6S~ zTH3%Luu~SXAC<}>?^;r-I>G_dfeSh3T}xxS<~9%7l2*P((!d95iz;k0Lgu=6py7sY zy>iJcL;E3;jBQhBdM(=ys%pOA8WIxTe=9-1Ry+NBckWHOxC|$jSNEM1&qXgfb0b75 zdexg(s@(*o8{r(!rtwx2ie$K`wCQpNR;iu!CjTqT9O zFU+SwY&FmCWA$b|s`<5lj32#H@jWeHM@iNTSPkO6lAHJv%Vt<#WDRea7~VM%I%_yf zgJ1D5#>hXVmeSx4Oc5>$hME!8xka_zZ)35HT6s8TN$`|ZL0jxTN;ui^)U{&JOffO9 zj1`#rrn*u)}@!1)SqGkUMJHt4PzeO&v*Nx)vtlt+fXsN^# zugUMK&VJn9ENA_Je6YLf^M#Gz#0gtyEpJo9#%fKyL~ZC~P0OpBNiH>ezV;4ovo_pQ z+0Y&A9;}U~j(@qOb;-RlB#@QoyMeePwz~bJnN@G22rikCQQsez-|SjEgOmIEU}AHJ zXQU$U@_>cpv}E>u&@S(MhQ@qIQQR_*r;4|ZuBC>Puidmblz%e)_QpiX8gk7tC{0TX z<%r+(*Evj~q9%-5ZS5Qi5BNN?;%W#w_N4NXN<%?dUELW zWpDJZSctK%pO-0@)>n0;rYPoE_C4n(KuFraVlT;isYe{*Y4M>50o6%Y^UAXR}UoEHPseR%h{0M#ErNGpFi^MWqH?YxdW;|yJybw_wO5qg5I!i zQ7zPrV9`p!ty4#iez1hSY`U$iIUW)1j9P_?VnQaAM?k`p8VSzYGIS<&(`iVh>sPY1 z*KBoV4F@yF1e$wn_c=C~_9&1N;n-|q4?2xH#NV#;HvFo1#<+0L7Rq1-)u!C1tDFw_?5#KtlpNtz)b*;`Yz|c?= zf|%^+a!`Oa(*WjsxR6Q(k&6;Bwnh!S6ANlSA+S#+|k2Bgb7}F0nlR(uDMi_IS zMTVT8&eKxtM;`;oR;%O^_$Hz(A~5H@-7%{tJ0qHtv&UQ%61vf_4AmI>u$ zeAqP~km90Y&gI~*z$YdRg&oG}H?^x~EwZGWleQ_*rzC$&HM(#I%N=-AF*7;oszYdt z9Tqeh=HfvFgPnJr@ea`ZqGSA$g^A?br|4`rYvU0WY%l_Mh=#BPJ^jTHKAjO-^lVipsF*(Y())n z<|rCFHaDP_S0Y`m!;+eDy{9%JVw<0RrrIGy*q62C**!49n)h_)P)ei;(+5?(Gw>*b z2cvt0RX#GEleQ`$Y}4|EvmQfi&*S^8>f`WCBfs=hF92+uk`K6%%hJE*q@}f3Q*1PL zZ?oaG6URIC#WbVvuWol@CoLZdfdrleS&2XUM*#Oxl1HXpaWwVtgy_)hB~S-sIdLlg|GDm1H9i}{R`(wIu4nJ_`VPz!sQ(LOhP*U zEeECBXFdLtE(y4HADz`+Z=+N#^hU5A^;_k@=6?7cqegj zZ-~W}u8i({K+3{pqX?9y&Z|xc7`(B`&kKsjSHB+4>gMSSY2HIrS$Q56s*abCP-57B zE*VpnJ9YQ-m2TBoV!CZT1%+HlN2pA*O;@^6B-KD2(BegFI13XcW7zH_>g#?>V#oeb zC=*?tMY1(?MLUxC@|~{{X>|4J5O(G1iA=lWB%E$Snry>N6^O^f$(VTQo!yf$@uNHz z*;O^3eD{?}$$beLC!KJ$5F*#}yQKH92!gk-gxaufZ5TZd*_r^}#6NV;dk{{pa`OW{ z&;QXM>aB?9LL>u5izulMipqj4bSEF_sYHtJ;N1g-R)Hj#)jpckN-<=)JD(Q8S4|y+ zLKAQUCca4>)*(F+Cj9-*C)CRrsrFKi4s19{{a6|wp+HTA$EBq8psKr3sw^7`0j^%4 zuE#>PLE-zZ+h(u{lN?O2w8TJ2a``kmkB5{Kp|ZGkZ`=shl<0e!&Mzd)=*dOU&>1@I#0X&H4Y{QC45wc(QLb7>)6d&o81M9#`bnsES zi>Ox&&@MW)M$)+67KXT5sck)J;4*O*K}vuz;bRJFF{wga1IOMPK*NPV3lk(o zLCEs}B`P*e2-Gq&8rm>)5ou}?7g8-{FbU<4Y;Js~ej0!|Qzf5BJF^%dtl)%dAH-Y; zsuf7ql91a3&;~BJmY2nJgrEe59aK=CQS|M$U8{JBUzBj114t=Bsh0yd^DsSw4naa3 z3vfx(-fqAF`~`-76g4{#)CMkP&=PE)p<9?BKPA8g-ZJnwHNII7*Kz@gm7B# zT5+`K1wo!5L8Ven9YFgQrJxk7h=`fsIdqdiQ=(mn2ABy4_Kv}zWa&=!ut~#)o;35{ zY2Y8T>R15=5WmDYbHPxQ#WVx-X)NR5SgFk@sE-N(SxPF6AtdixWU*~*1_|g`$^0A( z(=!AQowc_Rfucfm1%<3w$SOYZmrq)oFIrg$cE)r3nNq8q6G=SEN&<0qmLPKkRK$d9 z`Wj1L2SX_eEmR&;0!E%N%GKAQ4$AcAX4?bf%B0+Axk4J z_iWBd2hYYs={&GQ4ndv@^pc>!8Q3rtVnCJbqMqDY>)s~>o8U2-me_YxsKXe-g;!=G zJi3i~G zPpo{!gXnU>6I93z|MJ%qtUVPzMahsOVQbF-ulc2?d)YneinFF0WQPs2)Ji=d2ce|g zAWN)^2vYY!U0#5IGEo!v&(j5%z%wv~n^mBf7&_^~JG#Vi9nd5)cN4P;#R1;e+tpH| znKfs4g9Ne{xP7i-x|`jO$Gl>e+(N-l(=U9Um%1>9P}jjaC)G}oKvLYa{z>%|9$4jU zbrQo>r4PNCrm{&xdw`kay^}zumHnzW-I)M-$0)QG!2LPZ%lFTzpRMhauVprZVoBId zyt5-W%3iO%*9n$cBFHMq=ocMKVu0WI)q03O0DQiFlx?A)pYl->FFi-*whvAJ3RZ-`|0T)>U7g?%rSM zCiyGut6vuCvaqA>G#@%*h5WTAi7vo%xXn>+=G0&?r?0pIgD~;4BR41lk31c z$o?{`{(yTTz}!ZH!%_5c3J}b52oRzKohW_MmGq5a*S}qpo($^%pl=o_+6-=i_kKGr zqNWdB%571pg#|7ig$TfvBH9~HGNZw6{%7+FlU_MhBBR#PS=LsV-tqWa!8_{3aTcx; zxPH19vdbNIO!4}5{NYj|?IQCAgk%4w9Anzcx{3}?^(ENumHYX+e@|OicJ{qA0(TMwQ0Vy@LIOER*K@g4Hd$xK}_p`h8DF9We zk2cZXJ}Kj(N06!Q+d{s#dQDl@5>kanzvKc&6WX&*&?KPwr2|sr3^N75y%H8#j61u7 zpiwiZMX~5mp<=s);^94#8u`WjgkkArVvkrF5g4ah#4*x@9-LzGk@s8ibTnrIRL<`W z%tp=DW14x8ur9kMd{lArCL;|Re%MfxcO?&WwqV47X=8qDf1(r~Sdq~yxQ$nK4*Fd8J)z$xdl*Y2UMw+)7D@kXB0k>02p97^ z$h#eX9>Y2fcdhVX((#WTe8Ao6GI~DfnMVUnwbp+$iZ(6avr4=0TOJN)5pJee{4^zy z=VcBsdgk;Qj@Z^AO;b-O~vGV-RT-k z2Bp86TC&p`=n}Xhu3y`$^x};P;bu@`Pl+|wT1^wrKl=suE~k~%kf7szM@1@5x|X+#l~viBi-+ldJqA#6LZZr5d;KG3cs)`-t(axrVd z*>=7l63V3J$2xzQsfv)VlRH)tj@xq)p09D0R2W`3IFZs@$!}q3-S`cF-k-qre4)t? zwNJN%JSf1E*`za%`UdT{Jo|p#@Vu_T61#AI3tn{S{AF0lCbUr#PJZZhDFDU`W8v~q zD_wS7Ozf~6DzAX>mop)+esdtp;>&Lt8VBQPXj~A%H%qa!W(=}E!%pz|c)>k$rLm-i zC&Ndj1|H!iiOGInaCU01ouv^y@2q>$xWN5^(-5#^@*Vo+Tf09`TvCoQqrc&0<;WPC z?1_OtwmcZfcl#ISY!Y{Hy&kD8O%m6hLJO1+zuff+ID+b#a2E^BD{=r%4QutjOq z4%f@}9xv@Y2oddtyunxmh@j<_AI`mT&3^RSRPE5@oPzYERFKJIW9v&w`=M<&Vo7{- zx<^+t4@CmN)$~sVqs>uY(u;`2_(`dYQ|~^8S{o}OM$c6bBtKm)ogU5_kFtFyMSvWc zm+o&iK#PRGjiS5HOzQXw0a%=`z|g_<3%&*95DPjR`r>!BQ`?qOIlM#$>b;6DbkpMx zORJwp-ap>J{)$zDza>c6e?u-N>j%V%ppqIqXXt@Oo-!RGuxbBQxdrh8oE-m#Pz71w zf+ksz@kU_2c_yb@+jSfG)noR6u_jqq0m&K z|G0(yHRD(hFctsjUkM3N5#jl4+9`4y8jlfs8Z6`<#*G|{C2QC;YBnkoN$afTeU<6hFcU_Z{k zXD)eoWG{q+b~y*coe|dgza<>^B6-rm!53zXnJyAV`f~Kg-Ut4)_JxKOc3-^W5~Uqg zz#<&M5kNwSi3Z*lFecE!p?3xCyCu@Dx|nZY`|#&a_dXxqh{=!oO9@GgA6}Yb-R>yT zJ>cGS?3HU49TJB>Jj;Mo@;^lm@(-{G`eJiJ3kxE|t?n0WwO}l@++KNL08%X zqJtg+9;s>!4|gDmRlD%Ruo&)@eE@#I?bR7VHrOr$C2J5q##Dnz$n}5N%AppWI=;d5 z(Dc~wyMZG7LP2B*|3YS}&W`5r``;WhEZ{h+TL03$eR;A!I)Rr@XP@ME)#s1a^@2kGj{HFT>`i#uud9-Mg#{r{3p8Szyr1tRj&TAD#Uk= zu}Q^GC)99ju2mfYtI$Rw_%4SyJ@t%@(#hUyWYh;S+n}aZru=ofJ{_At*uzp-wyDcB zS1@GwBDT^TYp`;F*RDh2``zgUUr(|EY?>p&^UdcXXezn^%fq#Lu3~N|n{e?~G9Pg*g)s|CJOcl+!)HXxrXPLKa6o0vAxK~1O5Wj>OXZ*6-zy*wb z@?;u=xc$3qYA_XGt2i!ZpC24ZVjvIbbA)B)49-AA$w&tOEHmQNXVB4Pq%h$Wh>#hd z^4PyEJi{jk@pH^4iInA~FRY$xzNM9i_PRE+O|okY1ppbQiy1O>>$%qYO|B&fII&r1 zKdjOy-sg#sr9J&+PK4mD%>`_1o7`mW>yn^1U(A)`f@2pT{wE-y?_Dl3MDF8#Nr6Ss zex{hFIGDC=7msTTuOq}tR$F;9Pk?|5KGRf>38!2;I}uiRFj+;E{p^7A8Lobz z-7*q-PQ>ePHavliBiwU7L|48X5(Nsn@1t5;PKc86QZ*I1sM-k8`qMhaDUMapU~Zd% zQl>=TNI#ZWT+{ccX_#m^YlI@k8GAOx^U^meaS)ek?A4r~ zWy4-E%2F4cb>r&WX$my%fMmN4T&HrjY)XnZ5dM!JDc_(~N?n`p~jSfqJj-WM6U8kEbq!gh6< zN#V=;wr$>#Yp2A}OFTe>1@T5x2d|$5d|4G3H<~wCqpp<6r`TxsNH2Tk{o!q@IVy7r zmPFZcq9v?J&W~Dy4=JgAutW2B=`)F1q0eta{gBKlFY0;@ThC$ZIcz>`y9JZdr z)^pf;4qMM*>p5&ahpp$Z^&GaI!`5@ydJbF9Ve2_;J%_F5u=O0ap2OC2*m@3I&tdC1 zZ2dZH{W@&@I&A$qZ2dZH{W@&@I&A$qZ2dZH{W@&@I&A$qZ2dZH{W@&@I&A$qZ2dZH z{W@&@I&A$qZ2dZH{W@&@I&A$qZ2dZH{W@&@I&6I`aeXXteJpW(EOC7-aeXXteJpW( zEOC7-aeXXteJpW(EOC7-aeXXteJpW(EOC7-aeXXteJpW(EOC7-aeXXteJpW(EOC7- zaeXZD|A%9V=>M~J*vY@`Fh`c*|7?dTW`qEOnrxX6tCM;9i$GXLIZZp+?;dvrra`M@%zVz8A zxpE6PeqD2U0IbT9*sU`?!dh|*KvT+7wUha^(@Q_Eg}OnK&;Bc+xaZIt%Nm=1?6B{D z+hJ{#|JY$9=g*sUSeGX3#>DSkLjMTVfG;%u72gfIQ1aNAAJY52__s-<(B}A?#O~KJ zyInKJVGpBPUfVXSJu9`_7rE)xoH;70kmM^x({=lw;Outi;0w0>#*6IP|fN7x3S-@sH^9?Zakx?x8h{}8s!1( za<(E{(n}B+UH+4!9nKYUFBUEZb7T&}# zNgXg)p!!}m#d`N_k_2wcm@>ltUVW4{ zROdrulX?dl>wy*DIGa;ZnC*v>Bb8yDv!njXNvNw{_PN~Wwu}s9YD~=L*iCidK$axa zk2(8c)+%V)g5T$kD{s2%%YRW~O6!SbyL5Ta3+3~`MKPZYa_0);$K<%`J3!9QIDSz# z^B;3R-U1-=!UjX-(oNobmeQSW&3`*~MS2|k>Z2h>Yyk<4=_`{V6P@zM$mgw;J|lYF zBz5pFGb+9oD3Hs*S6x+F>j&$OGr0F%!Gw$lD|>sddCM!Goi;S7vrZq7stYo)6OJ6E zc&neh_2d!x(0uoh`$I*Ma+S!VwRK{$(YNQ>D}FwDC;iJle02Du`kIM1UeUwGCJ92r z)vhd=JIr$N)9rTSJld4p%eF5aQ7-YHevHU)@-%|B=Cc3Xpu6%Kw`o7=#=Xbc#szUD zJHs9&m}wrq?lg{w%RX6Ud!ajjM!8KQLt4!TpFL@!Wl(qOybq^fe8Q``KyKejA^PCRCZdvnhRG-i@@7)CVr~t34mL#0YKMQfR7$KBIFRC9;p)==Tx7%PMfPlA|x6g=6*{ytA^kHK-A{) zB^L&0pEU&mTXorD;xoI5IG(C!#JR6yqU(FUIDl5mCEca=vY)6qyGL78VZ}cS7$3e; zPy8b2h>y;7PYm^=vj!_ZtbkY*6#)6}+G_e`mp)~Chd7x<`Oq|`F11Q1zhm@|H9Jg4 z>ZPVuyk-B(5xIZtu$?lm?|EdK0*?XMslV+o(wZGcPSY(;^Zz-Vb$5Td>GmZm_D6m1 z{#SeVj;nWzE9}8GM&9|_g6D=z4*cDuV`AauAUn5WGc7tp`t)d3f~&yH_>7yroes!O zbo#-HzDROLV2`k3ncu#c5w>a}rFnEe((ToyQ(CVamG*Mv(B z*Yh@k4OzGyp-F6U`t>S1U1sO^jHiR4W)-=_ttwY&Z?5%Pw#Xx7gf6*r-=$pR0P($w zc?a3=)1=L(mXO~*LlDM`0KNl|;L=IlQwIUNw(=+Ri{UE7Xr*=)^zh0Np}Z;|gsP2! zFfYuTsH*J^x;NZWL4dU^j}3m* z**JscVdYN>@xKKq&(&ehP)2!85nYLp+ zas*-@3#JA{R*1lN^}`yFLY&P?fmjYKfNFdM;Pwe=GV%geXF=pO1&E}kVo|OCWNg*DYKgSd}u2RBwN2`YVrBFtGpk`k3g=E^^=%Y9?VYWZ0(MfVmS`~9+F4_ zh3yJazUFE#bwI#6+{qrhXYkW>BcB=6*X?Wp5S(MuK*`&pBrxhA7gLGZ;DmD^ekUB_ zAwuH5w8x1|_=SlrDFLcrXqvNAka$J8`5bxh%d z3ofpQt(LwUkS5<6beX_H9Yl@O)=gPYC9y26d`b@}2XP7Z4IAJ2y#mDHX4)NEBijUl zTU*{Fy(@0ENnMykz=hz$kyXPfj(kzoL@}AvoD8Z!4of&l6SgTgx5dB;Bs-&EjdpYW&pR;i>=_o0M29v}Yyw0X&3v>I z0M4Mo-XkC{_JMqW_*&6+c?O7p2emLjeRXM@j*{ZJl(($7gF;*^1-?v$l>(sO{NN>@ z-K%_*Piu->3y43Bg|IN=RL9mG&`KWrFbTBEimSyVJjEpB1y-629u#pD)czerBdPbN z!+!WimhmK3MUa{Is3uCFbvWS1!)fy!!$1l7l$@l647>>bK|U8{j)~@?yGh7tKC(w1 z;YUy1+?~5&0fY&)krIMBj3If0psgZk6C>N&7v0JxxR*)eMBw<@tTRWpjsu`L0J5nB z7vTa9U?9i2;2=J-f(cyzz6XJqP+)*61Ui}w8>|2~L_sPDaj6^>o>Z{oB)o1Q(0UkB zTLo&KO|0g)J^caQN>Pvz068M_Z35gH@Rqb!0ybU9>Os}40dI_dfH&UXz*{>Mo?LIc zZ3ednyzQ2jAQ~cGCv0sNbCD+)pbHG-QfUaBv+v7T@pT_Ng)>%Zbo8_krw4#}gRZaW zGB7TQ7!6=EbtC@6y9qh};oX$hcsG_-3ny()4)}LE_~;t%CMnFfDJxFsb)rBF>AKq*Uq3vUPo%mnuz;f?2~+W3#~#@{=C zR99$UO6oTBG&EmH154chTX>Tn{~LHy9LKEzZ(yraVE>C&{{U}9D@l`=2#uQ-*&#NY z1yZ)Ov)NB;H_$HGbATicV6tYyEt{JQahK}tZ2jFY3P1)7DDf;zYZ5oofIu5pStjoigP_9&r zW8RUV;Uuj8e$bTgGD?8)Jz#0FL9Z1=GcqA4#S-0anlv~7jh1!qm{2=>lU@ucg$kUe zU;T-Oy(ZQ9Q(8?{B_o&Hu7`l+DcIjPAW-j;o2{X@3O==TDo_wpJn+2-%`xMc31(&T z56HETI+}QBJRVA;NGY)i+tsQLL1>#eu%;#R3F?*1O>O44cu(jOr>RgV6_^wtI?vsj zq~CI+!d)0wXn~zc45)#y$xjyPV0Bo%=SGCw&A)*+{&l-=prdQR8*5AOI9%SU?#je% zX$hE6ta!)p)9s#z7Zd{i7T%aAEcS7YY0RX@63|QPw>u`2>f9xl-(8#_)mOOPS^ado z`D4SZ#6QAY)xW}<7V+k12(;wpFu@vAmG_wT;^OrY6LedD7*g6;}ZFxvBO z5+?<~%$LnIpL^NhIaV^|FdO)%WBOV_ggqe=(*1qchl|#Lw?E3d(4R7JxsUA+`YYg(&4|j4+{Y$%lm) z!l7n#oZSdskp7zo^b5WZJetC_P_R*#F^fV}cBG|^sNa`#KW7CBvp^~NqIouemI*7u zOr=#CttoPmC7AB>vitd=ZOzUyv6S4qVosvM%J~vTO|WqQTu47&&UtXE7rn?heprYm zSphq9P^SV}<>%6*+i^vBXyi_U!`RJyZkM@WjP|EU6Jk2jIfW+-^N&lHv&SPJ@x(r?OQZ*42XJRv4{lz0rg*qe`boaJRpbZUb9e5V@J87^ z;zSymdGU|%MiqcNM@K!LnqI->am(zyRj^hBk7xwR_;&Y{1vuRlx6dtKsvX5Rzb3r7 z?}pf*U+j!JE<`?E6W;vJKMM#N=$MrGL!Ypj{M@GI`R{AW`d0r6Z|+0dct>aw>+YBX z66*T5@b+rOJWKfG$Zlxjn(#(p)m8NG4q&DHCKnLK2!>LGvrkv05dq<kPLFqh9k!F#G)eIHTg3BC<1QoByTbG@ zYlDWxf{vtG4C)KaR0yjip&uwacL`n*=gIk}F0IjRzNW^W%-8RV`5IKPj&yg*We}a( z-2i=bDaG^C6A{Aa-~i z>QVZH18WYNv|51941g>OEEam6V!hz2K*sEN<*`k-Bg`a!C;ps!~9H#}dbeZWPTp%+|w5@rS`dasC<(D?14Boc(;byJ5Y0_`= zQ-PC1yN?su)>8^{lB+U%zHMFu-p-k9!5h8je8GiN+8RBw@utExjB3VZKrJ1dAU2*x zwt(h4aEi*;ccjmDge1B{Xelc9SYZ!$DLIb|2a_C;GrJ(jH`-d!*QMtjJ)@iPBVz+} za7mwbJa^V^WcuVm%W*35m_FL(V?Ts1k>AF4`1~Swm7#QNrje+3-KPid4c@Rt#q#TH zRvYs1n()RLv|bb5IPaGZ9xoxCCMvIV;rvnx*x5u$f7NH3aeviB0x++yIsL;*8lTw z+l`v3;CEc6`ET28MjlmDNRV(PyeQrr$g}{9|FPY=d!#=OZ$D&dEqq!21$Kfuf~UXO ze&s__+~iEW)SJh+#l!-9@pWpnMKoa3C9S7+tm(^AP8#6jP>2KLRt7f9>HKTvm6cTG>{rR{h6wd+PgGvF5Z zT0xzhTyvnL^h|TFIbfo+w;WIu_rBtwe&lKRpe+nvpqt;i=R)ZP z89ImBax_FQ_4TQd&haO*%Ju=vwhd~XS6$0C&EFXEg6sKhwEF9IfzN1jZwfUn1MLLP z3AnW~wMgdfD$2WKQ#se_rP1i3^2WCVe}wo+{JDY4gkEQ-Sr{CNLNp?ZPB_eLAJ|^wr+o+AG zx=V|;G(F0SPYJ+NE|*0Lox2Lns=(J(*X*#{3n~^NBrP{mbEn1LayIzk=SEkEHg{sM zLmdglQ-kr-ISBi%gVQ$1{Ze7+fJ*uOY?+`uZpO^#@AKf)1H(mj^HSEurXO4vJkQ#$ z+*flxt3L4vED=1u4HEtHOt;H>b1;;`EqQesIScM*JQV&Y0x;}b~dzo z^0D<(K5e_iJE4?Ass=yes@dyTRS>W8MDdkJ&vpj%X+q~}8ze1Rz*K&iTW46-gH^pk zuCZ6%=bG?2G(Y0GuL=dk+xn*Q_s0xB-fjtr)b~iQyN7yy z9raMLnQw-L1xa-W@kZunfg@z_kB9N6^Wxu_ApjBjbk~%8Q$maY5VCX_yZpB}Z{wcx zCdh3M`IA+!F!^Srg)tSTBN_pN;d`Ek$$t6aNjU9Ivh0^`%x68cuy}a|cf0eE>|W?? zfU{TY@Fi)M65NXMJTvr1;&r7(q1cQakt0`xh~)n8l%f5j_+gnHk{T&D5fp;vkq|wo>%t6`y z-+(}R?SfL|Xv)&no$((KvTn3;gi1o9{ZBdYnO;rj6%}Q!35a1* zHiN~6smM6JSK||#sQ1AuhEPM-N!Z?S=u*AoMJuBzn8TtAEJ@25x#FVw-cng1HXdxl z7os9%P`eiW^zG8BRV(?98=u$V&VG5wxfuo~Gk8+E9$+XQiQCl&Sfp|sOkDy{5|2B# zwzQCeR!J64MOb85F^3taKvjY*nlOv$62F0$xzmQ(fAqxoeO?^Eue9IOm7Q|jE&!AC zC`H-gNuH`Rm`+*&0ei5YKp^36`34h&4Uq-AYC%9Q)3B*?!jR3KR7z(<*{;QRFeH_V z`+2dGnRXAcr?U#CA<8r7Q&mm}{UJeO6fjvn-Z)V=+>AoD1KZ1-wsGNpjkqY&2XH|t z0Gu8HGVm)Y+w=?}>o{zmN)n#@FwZ6eOb1MIn#|%S*5`$)tW6P4Dil_?Y$x@O3Uoo$ zGKQm`bA99=3(mrOV{jPK+IMU9AKlc6e=N9~^a*IUrvFVTVpp{rk-qn-2IpbfI92ZA ztu+51v`2;IVfY1zPS0_LhzCOkX0m0EtPyfDruW4TU%Kr?pQ5; z1VnBBFoBcx#&!4h^ibjedWM&#Rk77wLkby z2rtju+jH_j@L@vKpdJ-J=SndUmLW_qJ*Mu?dCOI>!H*a}@*O2TbJ00Ph2FY1_nXYA zUYZgsT-5p4Qf*3AfQXp^*?u;6+c8d|3PlZWbW>`ti=$Up@^U&#j0eFp)bbOwk8He~ znCX9k*S!(Y@e|LbxoZG<-upWsSl5jiQ!VE<+-xXsBDkct2TA`o00&K+C&><8{^CL5 zk5(j4Ax`vHpS-ukkf;rHDi}dPg$-TSPx@4`W88CXT(Ch`k)iwXA-JyS-050j@%wRV zp&lR9E#e}#3v+CZw@DKm#=u+naWW~a0}^`tLz*wxmuaY|eRhTGW~4?|je9rPu*BUH^b0n&#a2u`%aL8l=>rS-i3O(mS=CX)xE! zq_Lw#Ir}~~*tO_J))w(#11-sgi{wMU@EnI`VnGrk;BH~IJ$?)Jvi{|GJ>B=V`LCe5 z&NIay54OL{tY+0rbhuC5c&FTvS?9Wg#oz9{Y-;kg5_a1d-!zU>GJN3h{kwh?oSX@|@oUUxN=|jKBCZQ~OL*|u*!b4# zD{g8*k1#{^jLgv#IAP$~3A4s8$}+eu4(SM$cTWylzm~|h{JkKq!6<4RDta#Tic)I?Q{5cG_WFt8t?jp<@IDA#UT;# z89WIclq*=sp-?|6+e@hqmJa^C;eX9aVmaN~}e}#GqcF#^MDZSLT3I76JCs z3XUD2+f-<54=DZQqVxDY6dl=9Vkv_|J>PrDyJ1F4Q;1llpScUGtWpY?qar?MnR6nC zR9&hw3^26Z3Bk9Fb2+_|BlheV9ad5dwC7UcnY&&h2hh$r#m!9C9r-Iza!164Urdhu zfl8)=-;lF0LHd5RX?@^Piq_957I;O2kP-~e#qP`&8y~N?uT+}OG*YEirU)5uRiHN^zC51M0B=A)-ThOC>c)ZB2T?Rz??fR{-7{19u77@sKZeW5q;d8YwlA3(!!s359Euktjd#B#1kZX1hAP@rOMeS1OXwt& z$loUNfKjHfJ`#~N;B!B|vR>%$imMd$g=-q2mZ#oH2K&vW>qipUG{6rJ=J%sE3yThL zihZFXgvzqB1SkS5mO27J)NE*Z5)s13DRijpUP9Kvpxy!ZdIx0_n#4iZlcg!OFWiD+ zKqMaTaCJh{DsOnNtD`+oX_2WT$47(>f~6ru$IVH!hyW#v)Kv?r_JMLt>LBC6ZT>we zB7d!HGH`KpN0O%+jwq=PEgN*PT^V8#xFC5B9;eiooKx*8pq$ip(Zv>L;W`ad!L096 z&WtpFJ`3&3LC7+M*}I04phsBHhVw3#sbguXsBI& zi^q;CqazEB*Vo|ARZ}ssVQkaU5U6x#R`(`Dka>n0bR*TF8{@f<%w0L_7M|gG+|sH( zlBWvhbSqrC17~s}#3dl>d2VoSGuh^?U2`v6lZ!@=O$9{9q}lD=9asJ9rI63*HaMPJ zyn8w<3Xv8PUzT4C;qQkd_`SP{ldK-`2>9sXV-vBD0arnf>h<~m!QOp7HMur?zdzGE zN$65T(|~}XDOEy8Kn#cqs2ISd*aNr}P%xo4C4dSlB{T&@3`I~x4NXuHLlFT*Ls3D| z73)Gk*k{nSuIt|OynXh}p1J>pOp-~?&++{oov86^+S}gm_~f*yz;;dygRwa48U!Km zg;2SC*<)7b`~+JSR>EfR{dpnT20ul?$;%=>u%AABY7{MjkU8*{xO*8gJ$EldCMjlo88W4pArnIV2QsSiQwPeUAX!7d(!$df?J#K{9ES0)Fc!cdqm1gA#iA`KPHBl^%VBq4G7oNeE0VjjtC z=!$HR*!?377~&BeWVbtsFbcCsX%W%M1sf`Y$BHr9ORf+yeUAd&N}UAP^tSe;Z))9& zxh*2vQVtggur*~4NH$`g4Rtq_cfXHj=el^HAxD@oXF^#0Bvd5{A4``?7o7-YBR>8u zeIeIQT}bKBf~Ya9OjyY(T=*sdHoV-SjHaxZ>0|K;SVKR4AjI!{DS-qEIA8Mzjw5C`MfXAWvMK_R*r6Zphfsm6Ui< zmsVlR;X5~R;U#tu0vjFO5C2I)pJeTAV9?*suF9h+<%uC3b-+(Hc6BQ>m+sEwCcT?* zTqH>i^UZ45=bskgn9y>-)NzN{dp|fQ-^%FZiw_V$>oRyQ&_>V**kn zoB{#0@6qH*dysMStWbgj#7H;0jSD#Q34<3Lc8G{^+k8k7)XxKvFB$PBdE{MKcuP8-fTu6vwT(sgAs!S3;wfhg1Ae^~~8-V8{V`V*a zuBw+}4FHFkn#gi<*4P0P6kac%U?Gc_rbs2175UR)el)3lZw_DnY+$s(H?fu&TDOME z=IW0Fqm-giCR~qM^ph?nFD%^kBZG0#L6wd-r4_Z2vZKXCDdCD8U!VqKGKGHTt{2I> z^xzmC3PXqKi3_8{VT-iXxw`CnAFQef>P##01ItTcUKE!mm8v*5MgAgC%U~h3mP}2w zZbIR7r5ZXAB`%HvEt5|e5kivb*a$2`l}9*v5piw~&sHjm;vx+Bz#{4LJTuXyg=`qN zX3pE3%FA#85UUyI6hk3!8s45#9oEaLn4n2HGR{S_;D_8` z>>>Cu-|}aFyU6s)l-RGlRHrB}Kr^_&1Pu>opO&XU99eLCWW~O($b-J_z|A#X zf5C_8@u1J?u%4)jQJR!J9XZZ8Cr^>ObrBd9m!6f$zGtjV(sq!oF-r0(-4JdGXIwmN zDdi%DH9yo;5Tf8Lj9BS9Lr6Gu5n(uAD>Fi1F!>V<9Ct|%^2OrfYJM$-3(Q`yEv3g^ z?la*(Bx`v=yDX|F$k{hYgcrOLAr_It<-ZSv)DEM}^rZZ6-x#Mrq?vn5jZ~xgP~+!y zQFK?8cI+A>HQlePI=L5~EGy>T%HN7PyR4Wt@AvpD{e(&{LF$Gc8hd{-o6hwZ5 zU3>UH6|IoZ$^5OD-&3z!^V~mwy_dkh z1}bLfcCz*Y`pMDXifKHuPP4(wT9jcikh5fke0{(`V_7jtd)ga|B#JqMgdW2#D<)T> zn1?~dq~GPDj@*!Lm-%FhMHdp{ph~x?C7@!GB#NmIDyHx}=O4rzU7}w3A;X4r6VV;I zc5dY6vW^@625H%ykCqiPWLYse9v0Tz`#yrM*abLbSura?#r%3|_gb}DP%%X=axL3I z#r$-k9t0vI3q141Z^hLArI?hMT-w94pkmS_im7Y~Y)-~-mDyR_W2KiBbKid{X0x?P z<+5TXIHC@_qFvDv#hg6e#p#CqVVyAfk75qspQyIq2Ng4ZSurcOkt^erFCN^jX=*CV zZf9_}Mw(^y6es;s%+EVwh`yWw{Nw8~?8|}&AYwKyX)Y_KQEy*uPa4!R zWSS_PF9a1+?`N-*pm+S2Vv3$DZX4*C>01LTCR3uA7)x?OC`!G*`JSc$B-jkU%`L69 z9z&8SrqfQ?y2?R@P0VO{AE=n#Hcx#P?t_ZyXFxV=durt{xKOJ~{YNpKnwJ%mB2i3W zSuqD+tV?7+IkFRe3{*_C>jcL^#S{t3OS^f8JYR!~$$EK1Iy<`NrQqz4S7!0C z`TiDcvl6J7l$aeAkf}o>q%j!gOTp5_iybNw#VlVCS$u_$cS4L0nSTlDmm<4bQ>&-^ z8oS;1w26B(rJN5N+(KM@wx@iY(EH3$>6I-!lcE%`+03q z^g=hTU}l*x3vRE`3Yk|n8%%a%1Wx_lVBOy#^c&FOScTA8l zg*p2`!lc|^<(Pai-^KMBF}iUIBuw7o_Jdy_V>A7-;aBO`P`iE+CNMHxFi;?B6>gCb z=4?8#ui94k!~Kcg{lhV&ndsCX0s8$8HeCJ5E8f);fOrT7SwcN(xP~aE56p4<-mS+_ z0EpL82xt7QXs!+SmJ*Z6pH>WI%Z94X)*=#0{@O%_4~t}1&hQkYC(qWwat($9_-Hi( zU0Gb?*lTDC8-K(>@*IFa}Zs;rws+RvG=tcLD4>OI1F>7gm zT`9RB_enJ<3^}29ay#E`3Tl@_;qk5!DtE-pLN)N#0UD~>cF zJ*6@DL}VB5WJ%fG#dy@3NG970w|zQmo4)9|0CHxDOQ6j{hhEKJy{gy+pX%KeS@xK- z2Adm7AADxpYGRJspB*YnT$_TvK@hE|4@^rnSpSED!5;P;;y4mZX#>0=jsTXd})`^~(K~D{{tsk!RySxaxiI0y-aSbw0oHEbe zZg=F;V$75Wf3SM3@{?~jcp3G@gv0&B!^K&1Nw&`Q{U13pP2t7yBf_-c#1&Lp)jC;y zA&@Gld_agij=UJ3rJWxn84nEc+$Iz@tacAFc%#el3^qr@sR(_~{BUm^yRCQ2 z#z@~u3uW3!*WmW>r*d~L=`+kATI|PXQ67^rwPw5XEj7;naj31e(1N=Ay7F}Coh;O* zf&(pz>5g6BD~>K$@Sa~>xn;&F zx#+`#_K0H!s+hM=&&BE*P((euG(OTs-^#X75ozuob`Q{R(&Jo@%bVgTTcdk^JX1eg(IX$Hpx-t2@wS0^5lTG|$~?1I-{Uz|4d3F@_S7`% z#3$)Tj3<{`;zruD!zY!s4xWPUIT?O$?W{#+*NPE1yy06-r);|ZR9g7pPd%W-@uFg0 zk`%qm@vgjVi#1Aa``@D#K+M)n3Etmdb5H>V)H@0EH-h9$b-l&ts0@;8pE?GfDe=n( z42fS-zJY!zP=D9|mWm1k{OB7_;TbJ1t$wDH$0e+zN+}GNyd82X2S%inMo5b(YSqGI zqvk;O&pi8Re`ege^dj=MS@;|8Mu2V#C-s<&ef4Gw5_$Hd2NHn zhgQ_CNWSO5HuBZT{Bq6?|F0Nvq;Fi}Iyu-~52qP}A)sohjN!$RPFmiO*CY5bd`j-0*2FSsOfe!z%7 zhcZt>$B4j;w9gD$@IEj1zQvNL1<;R3NTdsiVY6D`k+>E_Y;SjIbF2CqIslClRRgYH zbk}oZQ3e#wwq^+Ov+LyF{s81ayw=6U;>(IhS&U4;UN*%V^}X+Ascbu?;PXiUDcTD$ zr1WJgOW@K7giAUe`k5mIi0mYA`Qbf%S^}5azu}T~N3E;Q3GiEFvt$?$dO28kNRHn15h&>_=$5|Nzs&m(r;XBbN_{qZYpH z$BBiXPF@{~32Eccm2+(8M38MEV-XL(9rD+q+<{siK2IFDFU8L^x9%RyKAP*eb1kRt z?Es*`F3(K$Z%=ldp)0@t<1eXWLO4&%bn&6W7v}hEhDn~xX z?6b=*N}3IW=~ko4VjCi~p@XFikA|6a^Myx~8NNJX03V`C8%xnVn}(_w8ogktnVx@U zQpQ$fB2%>QDhe2aR)`tAuMp^_Z&Hs{KPAC5sVfc2*|>@4xNU{C9IRlamM*3DcDqm$ z$D$ZoQ(I-`yi)%(9MO_VEJj2Lq^#%Y{qnx-@1(H`|B5E9dmf{>Ql|gD^DS{e_I5h( z|AAf>CQJ0Pd1}pn$C&Hm1E*THV39^{ZSp7CM)utl+4WUHaittvxca)Uu7QEO@86Cv zD5b`IX-R34KN|1E_G-Bs?K$hkV6B8nhc0^av#C|UXmj-XjSk~Qb#EPUb3@U?T4lsj zIIdtgOrxML)0eFx)sdl|8hy1~KH86oPJE^4_?0R?ZhGIM#Bw>t441^1yG?(^m@4aM z*6bsudlFAAl|RmCU*F)07ws(k6boCglfRe!zgPAB?^S*OKfkKa^tF_d`b?6{i~Ck< zfir&d47P1`pMnDCBW-7@1NJ!j<`Hz-aZHd(a4IBCSi zahN%U<8zo)ZCcKQhbktZE(zlu;|07ALb`qs2NAgdmA)uu`j@`VfL6tCyKC%4H69^C zXrilejCS|wmOhQcZMR^;Q!KdQF(DR^Rx z8GBObb1JsD@)12ts<5;L%k5~9zl;&a3=~QK=yE}OjG z@aEz1z+^B~s=-0pkTv)|;P0}_K!UQ$ zi_rkUQ_howP?358@dc034VkkU^DU#@59xR1Vk#2Mxbb_=4%YtwuA2a55v`fw7^!kP$TZB6M=1Tcm_&TVsjBSr-7 zZNU0OI9xhc$wBT8lAT)rMY*_Eb%pV6ooAt=jl|HnFa~c$R{1)b2MMic3cD?}6yYGf zhZNfHX{V+jb}{P?(Sy#yi0jseQ?qzPD_>EWJU>CdoR&r#uu{*WIl0*V=%iP->nH%R zILIn2$z^Qn2ik#R+>4e}sVdwA>nu|0_5+d7>*7v`eQ4XkS*_>(d+5}IbVM|s3B-ea zFOm$6dS<0C!GW!v3r#Mbgzv%f94)*`^_zO}ZDHk9V6~r#B=oTR(a$8ooiRo)E<-+pe z{YM$0_Oe}T;>?ClNlH_t9wPqUI`z(YM@R$L;OIDfk%@eKoFKIoGrkITo8+NbgG&{y z#b`S48>C+q9Sb*xq1dQnEodoHY|C!QZMIY-H~QOFj0O`zWkVOmkkUr&BgYBtIew8O zByEBiEruZlh}(gHl>qi|mcpLuWr1JlF*A82bWva@CqzyS5` z-_n6(pygM9%5)6e3NPTLNdiCAMpIJ|2q0@4UJs0_`nIK(AWoEK%8 zZn=>l-3H!Yrdv^LD|28v=sYN11BBPN^D@G zYU==70YRRHC}X;B1oKHn_?85jFLb?rZG9>&{V5N)xqf&lvp5vgTA@U1 z+ck^tnKBobNVs{@NumR!KT_ov*B;&PIE_K)1fvy5xb$!!T#)~Dxjt3>lAAmy+k}!f z96MqkujdlAjJEtzD{h7EB=H#6<|Pev;+_7Y5IonvthW@;9!=$*kc;lU<#amT%mJeL zP7`cUuYe6If4M~UuOB{rOt6GB?^PqIOM`eZ=CFzYB=Tmx(Jnh!~3@bYxdS#S( zRl>Nut2qu*@`8%teh3KuswF;6I*?|OtHg6zSKDa$(cG%^V8yQBLX{#~C!;jE?&5K; znt#Jot0)UFOm)9y+aiRlqhmqCZr5`zTUt(38%AQmC>U8B4zsRen;v?= z11By^3RS`70(Z6kI?;YIt<~CKg7JMv;F@0s%8fF!Nt70IaQrG z7q4z>#~xv~ri3G{WZ(`FU38XS+QI5YaYsAfmUx?B>3$>sVEV%$=^i;d`3921n}xOE?};Gq9>qcpu6m8ofPm$DCS#j02DFEZ z4CU#dUfGrt4NCx=J4d53@0{F!Hi{wf-S;zg{>-A47LrI+eUgxHp?2OO^g{lr1JBToL(V*@2`3MHoOA(vsso5gCGVUOZYhSDwKIvsu#DKDW z$jy7@zspo0t&Q(Y6Wf43HVo>+#x(PL{CNb52+c{x1V&p_v5B#>$ZD>QKMnXZ39}Jz zUOL-;f5_{p0(|W@@=orZ>-D$zR?)XC>c3zY-u_}%*d++ZFg#P)QLCB z8IlyLM_rO%oPK%cvBQfhVycLk4rss0yd@nG+po(oq4@=$s2HGP@_-8?khL_C z8BndeUKHn>J2eW030@-HQ)PbkO^(Sbs*z>u$81c-7i(2}|KVNOD0R*m9z}XI?0_zb zI89*;vxCu%AI9ex@V6lEQc`!>^vxWcP=siw*G!OlW%x?3mSj*nj;d#HjdkMhj01?F zXbXRlki@_SjzV&U&uf!0O_hXdKFsuRD<@)tz9jAN$bzi88Cq4P82X(0L31*^q}~wp zT}JDPQbOxLk!pgPOEYUKIA%5bD|F2aG202`-D$dXH^{qs!9Au`5Qd=p>e(UY8PBq6 zkaypCe;}T;BWry^Z%~u#YwG&>xN)Rgcm@vTnDdmlQ+pOkGkjVGmVU-lh@R>7V-5-r zyKf>Ts{pT3Hm~_gAkRvl$xka+a~B$|!&lpUoEjM4w2-?%?|Al+6z`=s4MwV&GpS>@ zj9id5hyHqS^aUuqg^!8bDaDnZWSg<6)peE618m0II^Jm(qj$ZPuMmf}V`G!aO>wst zS)npU(wjId0T^6Iv|(V$L_>wBJ?D&^Up*-IKzOIe!HJY?Xkbj`u6w^o%FgZ`$Zy?h z@`YwFIvM)KBE$6vp*N_M;Cja;o|J4xnHgqD8(Nd&$7J)ZG+bivI`j>v!%$|M)KK@@ zb4m#DjHzOvnrZ_OZo4#fJu&YgIubq8KN9UV9dCVkEaMIJ+@<_Q?Hi{K{iGTc-T`Y+ zc=^NX1CZF8=M3MaJN-qvQUo!$E)iaMTz~(MUd*A)05N=HUf-M$s+n)ETk-nDZqXdO zkan7^w3;0F*WM#vAQ`}W3xlg&RCpBdxqyx!0dJ~Ki3)^}hY|kItpz_l++{9Z~ZA)Xf^Te=-hIrnsG}p`N^VP zGeCO#bvkYGiMnk(a??WakZ{Z)@yo)N=Z%Olr}Py@F%k7dSMEW(@2VxdOm*xjY2K7q z?~_07siq;lE5`otO5@B?CMO@%b+B{n5~L8Bbs6`3(ZMTD0=*RuxWzLcaDVi@>oDK` z{m^Ko=pEz~ylGlvr7XOsV9uW{9H$yQ*)WpWBbPdu*aBM+%&is=tN~6Heb2w;pIazX zz1_9_R%*wqGPqwo`ssK0p&t2yNu{hG$NHq2isl0!Rdg}!PsuN=9~EtC8zd&U2b9r* zkxLV;?lRiK{=o9Jq_zI|#+L78=U25RHB#66neMcQZ5M?;K2mWn;;P2_;9wFQEv$Wp?ZtGgr14(2Bjs-fy%;v-Xb> z(5V9CCCyZ&5NU;7rrXq)7RVaIiMi#Uq$mySr+i|M=;2k(mN|{buHX9aBMZ+zdVoC4 zeBtOEZTw@*H$pW^6t9#|g^VC4_@`qxx7E>M)Ov#ht(t}>(i9XUlMnNp@lgt$z)5k7 zhPpS68Y^98Q0uCE05aR5d!jbb^Ji+;hKnU(>}>-B>+6kw8F2na_>vfmSQC4>N>hSq z6=mxOe>tfcZf@fNnr9HGhG9=wQsbKY*WUT+(23rG^J9TYQjURpwkaM_4I#&ol4lDI zCxNf&!R^i0f}0*Ju=1)R`%RB@&tIrTz`U*UiexmC+kCpT)=jsWZtFhzEhZw+x3KQ# zit+G7Z$azVeBD{v^FqJQyrdr1ovdTeLywU3ao(Gr{Qb&kY?}Hsifoo?icnpW2n6gF4oyeL$!e|7rAUkR%0E32XU>YA!yLQ3>|T~>GO-l?K6 z%+&qY<5voQyw*OJc)M^jR&2D`dm0MV0+5e`w_#h+C(Bj@z%;U!&Xhay_J`6l5p!bd z>l$jD+-K+}j|pN~B*V(1%kH!kaI3e7YPL!g_gR{BTFyHeHH0o$zk5t~#dsGAQLd47 z@KgJ$06J`IkfT(o@GR#P28P`$u1y+nc zc&HLVq1K%h*nMIpIH!*h02JKI$t{46N07p~Zyb~_#70OVfv<$r_ zLdZ8V5iI)30=7@li|IeeZFtLMrihBI%093@iBT2@ zzsX1Q0l(wlM6lf}O^#U$mekFr9w^rbqOHxpvLIrV!d#}HpetDF;vWawFB-=moix=; zn0g>n51?_~4pEDOxHm7Q(Wkl^>K}y7{5Y)l)M8nGoi;7&Z!oM+qQ7L*>3{TBY6J2y+VInlFzd4$47=oNlFMSL zitmW z@v6nOFOz`U92|pVG1s!`asD5IBOK1r(T*V{Hzpp|z|ohDOt>Z0eq+s&Q75HX6R|0P zB9};o(v#|f_20skj{#SGUne9MnddrQo8^PxJfod?O6di%snSErnmx!624T*mE~*c~AG=7a>t?dJ&GLGrz8 z%}X3x>x#_^MCXLqb^F2c|1DM9)~*oz%WBJ0d4HDO>OK0N z4Rf{P4f@iHqhJQr?PD3lMitGKUtRgC!0ce5q< z%ZNsVcgwz(X&5|zds(0II1x3q`G`LQqHu9q7h$Ud$oZZ>=S{O3xnpdm!Xgt>#qlv` zTc01^+tu85h@)2jvuI}OHbS21;du1$O!^Vm{ZD>Cb(ztPk#}@ye<_fb(O35W?gH=s zqHl3ZMrq5da4BY~0+R4U*iXr`n{7EpKHJdmn%A{fIWqMed;6&;j~m@mR;{eiKFt5B zu+v$dLd!ra;xl_(rS#uI;<4hod;^b}QkZj*cCI2D-(CtXd>NjH0IV-F+6!2Y1*lk_*a)vELndb9Z zZfv@#4PWk}Z!5Uk3Dub_My9f2pD#spA_YbV)Uo2uEpy|VLe zfM+oRb;^s2rCE^winN7zd?DUuT$n(Ng-c zE&(Kl(YEF@qr>97e8%Wsr4A`i_3#K>Q9IjaZU0aT7eayhFc1dU%HxB4eh&$A8}F2r1~1a3 zb`bjctqDIQr0Y%Sc+ zmZ8l$8DFKIUaoWjl{GBEdPPa4n_RfSqO=F4^U^~U<2CQQWpJeetAbzK8`(3Q-D3ik zQo9qk6HPXi+D&c0mfUK#hXE^G3ezn80$fANi%>G8FzBpnNX%r{det&VyxPDDTc6Cd zKEpVY6kxFGrO{yKegX8tEYc4103cO;BflO-N$n9sCNZHcZ;}HFC@? z4(mor@;X^0tpT#JY%`Of9jN4RZ5+OzD?k0C1Xw+G?z)F;D$GOkY9!lP+K}?<-Mc|q z9?QYtiw1_#4i;Je@^~4nIv($+vP-?~S^MLmYPszcs={r&_Oy6|QWbrV%0UR4%5ai) zy9Dn2LY8pYyS2y#(r)y&Oh_%bhisbkdk;B5J{w5a_0hoWpwyhpW}*zXc}c5@Iva-m ze*LeBgIV!xji8Bbcl0XW|Ghtxm_m0jSnY+0RAH(bQd=~@O$@)kVRGuTPO@wxh>UfS zVyT+$Nyzq$mdaV#qz-UKnQ`6i#N?TDa7Nh>oKbd+On7A8vBw?nZzy0YovGHO74xvG zlA%)l9|3(vFY%y?piR%wVRa7~;*>EU6U>FIz(f*G-aJQ;>@1JuWEK4=@!8%*)E{Eu zV`Ss<&vhNd;pzLm!|l~e?p)vJ@(JPh+2t%Jp=0m?B$&3B=iP8)g>QKU@EKYyP<%BaW;)$8ZKl zXvN*JV8)BYFNkrbH(#Vq6hPz`iXhTd0KNBSoQkt?(i+7}kVlFMnpxacKaXc5?2134``nt{!jo-@%UJ(|8SW?X6;bfW%xSP41hy}0Ho)=RA z@TYyr>M^`&E(NZEhMBPg-}<|?%Fe%LJdxeFdQ4gYfIGp>iy4Q#818ZL$PgOj{^gT0 zV(cOdC=xjii-^Vy#yJ3gj)r*q%yR;Q8WIwd7_t@+6D%F`nu|^1BGp+yuJF{u<8fIc zVuOJAx=i~juu&!=ZtGFPS`unqEKDnwY@q@DQA>=3YiQFU=gng6eVsP*q?ClZvLeTM zFT?$nOC8l|9G`9h4F{PtIw65r0n^P)iyV^ zRU!yJxy1hiR`VSHUs!!M2lMbBtmaK2$Bykql5h*cG?ak2H%I#_8xhV8+H!Uos|Ao+ zF6I^&(?=m(U?CK1PS1;_U5!?*(NH#LK?-Te3q0b&P{v|8ktRf67aHk`kecT481={v!ck(?yrak8P|_Lb4WbMKerCqoGmF9vGayux_gJDOP(9z3A%SXP))7`zMrQ^X z27?>P%%M{gOM6hZ9b6^)##A!)a-FKSh`56bml4=+X5qk{u#X{-x_bKwP^v}QghWEWY+1JEtG$u8e{ekR8xpPB21My zv;Y&foEfLCy&{Y3MCbYCbwr*ACzF96m_@dfmiUllHJOIGz5!CdZmZT(Amru-dv!pg z3rvmKRwj&#zf$AVn0(5%f4o|locQ4ISHHXwa5kB;f02%@6m11(lOy=t1!1s)BBX}7 zJebV>J(z6sLlPN(`B6y8LEgEU_lvCCUDJwz;)3B^urn@R?u^-Oh`|uIvEl6DWM~aV z5*c^Z0gZzavetihfyub=(cwR2y%uI(Z#Z*)Q*qX6$j1ZO7@d4M3q{z&P9s~6Ggzf{mM3elm#X(f?|ae!(K2U+Zb3* zlm%$l-xT3%5+!yWvQnQaO#5xur1D?Q@o&4Pr(Xu`8VLJk*X+5gKlucPm@+;_3@ipw z87}BsQ#qmeD>!}rAjOyc=Ih#P$6KzC^6MmgEv}RBHK~^JY?-fRc4>ipO)8i0 zwV-OOb|MK;Q6Q#cfmaQ*I2A02pdL3Su z)SIpLY1gt|JD6>*{8z67uKw4)@)En&?e@(P@ohi$ohP(r%d3)s<)z+R^P-#&|MImk zTf*1;m|uKtb?KjVW#&zvCZBc@)RaURS?23Skgs`7rh*F_DHpnwGvKcO2fkkThp&gP zq7X0s!`Id?+WzHhV%44Bd@Z^M^7TB(*NmGvGG!oN*R5OT>z2k}eEp=UNy68ndyHRt zO=>g7BSv{mex%N@?mAGfU9F{V(C$dHYaTa259fjV$~9*;VAo^TeR@TSuuG8^9^o!80hF3ipA{xz@+NpG!u4h}5yHRoZA6ytdY)Q*L+ zBf+&=$cjeWPUE%f8lirqYwS7#$-0}pqtkT(e}jc_qyuo0R5a_!tcuiE5BP2tTza9i ztqSEVf?{WK2TABZAI0g^K7Nntk<`hw9{OjZaoK@N8J0?f9RcgbZ6BafdQMm zS_V}_g6l9UMR;2}aA$UVufoPcdk>hipw?z%-^l82XJ%VFlYk%;gDLZ1g;h!kMO~j< z?-I^9ZC)0I@grUNddtV3j@M(g{n}Vwm)B;^_nE+%2k%6y;I;qg6Ux;LvYh(q%Yq$< zGrvR{GI&??b;ILe8|3QK1|d7iy905q1A|Ah?=6b)qu@uHcKfWVd6r8dSSO=ygB#0z z629&mmTie|0N`@-G^(KEbYGe+4<*xq&89pns6gami$O&O0lQ5ti8A_f;O&Oc4C15U~H zB6g)Kit31v0F!oC$-wfEBg%6FI{4OkFiloUd3ojm3| z*YtF`(5goA%N`d8XIMc-{yvbel~!c`bVW(OgvRqP{L<^Siy3;6Q7Zz*YQIEWrqp0S zz0MjWfqKn(o$+NH)a%o)mh+goG{P60rQC)5a$pc_?#2SiB%}69%d*Wu7RQxKT}Xq8}(= z6O|)hR@ywfbB0WBRcuuQzc}iSpP`5HUH|@s*4^w7pf3eJ=W%}o^Y+6|gM3Yy)=R8`FZOwe zBV7O32;I1b`Dk&8wa0Vd&hbK}LKfg!t+sIJ1m%0AJ%z={uFZ=J0;Pm)ow_ZxUpvFyDfL z9kocB%{r&`f?w+1|9&0barnF8aT6zce0VO zpX>cd+)e7rxRtwY)7K?G_=4+ma0@)r3*NQY{DWpqN1pq7s@45H53ZCgVaD^9 zDhNV@EAfI1GwxSVux~62wwAR<4=C8QO`u>m6SXteJeCMHUtG*=s3wqL5#O|Yg(ACH zgRj%8CHkA(sS-51t#{lhU2esX)ip$fBbPLhj>lx$rx10vBsPnV_{JVW+%R~@=JU=g zW!DdzqQ?ou0&6S%fxjQ@(&uWc?AaaFn`BFvXIGW#efBD^)bVQn{CCxMk67zwYe*_1 zZB?`ZJp}Wv!YPwyjUxRS0gR)P5Enl>iPm)8rTA@&iI9zt9X#uAHY-!ynP9ichr&0D zI3I%Bq*@QWZjo=*jGldX-^O+Cm~s-O&S3QUK{*F(5L!tuHHc%*RilbA}-HWBf&z6le@BPVAo9g#iKG}66di$RK7;Q7x zhI^e+2fnR>q^ijwkFy6|$`W&&s{2vUVywQ<`~wNfDPMmkHhJ|aHOiWjXJ>{{SHIb( zYBfY#zHs4GN{N%$hrd$ZP)KlVmVpc2lyL=4Z0bpDnkDzD-&xs=22R-zzfH$)32SXL za7`}J(_gry&C#c3Ph;fzKkr`UFdH74r5a?4RxXx>Jkh`%Z4QBzTY98d{@7Z~Ok8oM zJM}7DTBv0eR}X1P9QWr3Ub|EvFnMB=KTxY~U(g2Ai=m`1xpb$hMO<@etDU2|Rxg24x>lsHqrq*Sud19dE9%(m$z)R3Y6V@3alH>L{C0?n6g24i|!fn z#6gEGK{vEmMTr4&8H0-Ye1ZMWI&a>#T@K^zg<6v*^~-xxPiLkkln<5boVqU)4pUnr z2rQKD^N}grADyPNS!O~nw*O|mU|mb_H;ayJ%IRile4TV=vboIA zGoIA`p%l|Y$lToe_x?1!HL8E|T;fswag_*?X)Enl68BuH;;&MTtf0$V#&rOOdb1hwf*Xsuc)36EzJDlTk;| z2km5ou0M*$ol-3NR(Q7-GM;&mT1JNuZQ5xL)deZxp22ee61Mz~kgUTpK0DO6IYrE? zuUxn#0tx%3*lP0iI6c70e3jYX$V9yiK6U8i~3KxJi(dNVtJz0_2O#;jOfR{$lOm^$EQ2`AmY z$`h*`OTsqPX!_I_GaYwxwDzZ_?QD1CD9Nrg+Byk$)tzw5GEEwDs!~3^JvcUkeg3Ut zn}%g_i4#^_Y57oWX4@5<_kGAE=y3vd8+VJwn&LQ>5P{*=QhHWxIqIjy=R|ILnzq7c zM;U)#@r9=D4R}{Vgl>A}Za2#S8P5KWF@O1~xW|1r4YuF!!Xf&~ z<|1w>teg~tq1YO>&SBTSFXgj|`#k8TSu3>Em~C!zT&Law3k`Ky`bGKV1cMjTJvjaQ z8tGjeS?#av^;1T+uO_$2Jh9tws#KI$-wFWUTv+@{Q&o?0HRn=V(q7q&!q72}hB%PY z@F9$+d<~6U_yjxRVM@Iuc08VJoOoK4T(bI_D^Pj?ovBvpvvDBF#sji4kneM4$-LB7 zx;H-MGY>}TYUjvi_NlmrT(KkwzOAo}^`>W`tVJC%AtSN$?!W@uu3qossleW+E~Ens zXSIABQBJOaM+&VS+WmS<{u{Om+gC7;=f!>=jz?8dq5eKc&p5Mym=wB`t?$^@n;%V4 zk15F-)?9CAuGW&ARq{JKOCcm6IS4T0Ond;TWds1#VCS}N-+a4QmL{)JPHHc5#L=dl6`IoEj{AtMSbKp0 zdf(=w1(}K8D&7rQB()$P@;sesnpGde<+Z#S>=I1dm1haSJIdP(zdw(cEHgIgWt^f; z)RF8pzZhH7Eg+Q>v(6uh6Hs>aasWnpmf%50oBHI`#WeX=XrskVE|I79ZRitligty* z95J&;{vY<<{4K`*@&BHEt7&Fxs%f8A?Ixv7YT8$s6cW0ogb*e|qRg~!YFcQOX^~2p zii9xjNf>)2j4XvPWw}D?d(KQ;-pl8E|8(E?aeR*E4>*6CV~#mrkJsbzybkAyBxVCC zk;EL>c`lcazpMG=>$gfgA|_q|6vEo?aYrM1b}VHo6~Nd!`+GvQBA1_hS1-ZXNvt`H zz2YE%v7f&@_X}f_ZT9-uXyZun;lD6;YHqp&V_yr{l!AjW!oLCaWj|Z@*kR-oVyE^k z|2S$BuM-YG5P0t=!4=t^0WxE!sDT9po`n#-qW?V9V$X`#)B+8o`XxPv23E_0@w^slBIYv_W`@ED=EEdsr@26%(64r}bWHKWF`?eL3j z+hl8=!xJ~wnSVTLIkO&m=yMzN%z)44aQhwTRzb^p21-%y)L}Kcc4f53#j6V(iN0$nYe0iEI_Q&IBd1T@#BlDpx*75Yf|0_ z6OWPT_(g56j!VgAN{zh&-z~lDyn-$5jCYax_OQpMEHL`8`aWnZ;j~%cG9sRhC7uO@ zkYfDZI3bl-$hLlgY6ov#6-Hm`;f^ch(=&PtyJ3VbR^58mp;Qo*ghyz;;!0Z`YK81y zUK1hLyJttmBP7vRc^Oib^8%f79a4|Ia(Fvg=Fq_Rze$?aiV;+#Pjm%p<8w#D6~*z% zt8~;a?DjCWpMXwj^l5C2ehhuNgB6hIn)n?A#vQrzGhK*8*3|RwLF5IH^M=K=ZRwyI z=2cK3F;z=rYu(r9pj-O!3&v7bFqeR)k?kc*q{djY-o|^QsZxQ=1}B($#Wk7wRE>n= zitPB$kIhgSXU?QoG9~8nJj6bPWzU<-^ALNggS_Hf`)r7>!_V-J?zFXGFTOrLulfG{ zBOia-*4+OM5WB|3epPR~!s`v_xI)4C`~V27;tlIGzf;zY$0X=$DlVoa%FX^ax4FZ( zstu$VbSEiS*lv~Bbs1)sWfw{6lw+8I<%2u^M~JOX6hZ8D6WJ!EOnZ)*Ee14Baiq#u z+Vjz#>ndganN^t6foOzvsKO2-R<&EILb|ZQXm~LW2Tt+ zd38J_shZr+ggl#ShfSKXw$KZ2%`ZiMI!I+G<@KrWyyb{a2*S)oDl4VT< zG+37e)2nwf9nV#$>oE}IPdOP|29h^D)^da#tGKmO|9R$>;Z5e7z*t85y(B}`HqZ!j zHh#Mr6uE_}?o0n_ed9|daqDgf++!k1!L~zIy(MK4J4f0SRzbQ(=P8}F1|P^wf$i|V zS9^CdPr0r=`&(hWw6Y*It&a!Jp*b&|6uRpYE93t|we}aO)}sUAUV9=jyHGE{w8KdN zc}n<;17`mxuJ#?@g}K258N3Fs+#5)R60B1U!(&{xWQsO&Ap&3{_iLMYBX{~`N`j`s z23SpfyjBaH6;1sDfCMJOS~L5v;k?|x3X?UPo?>}`c~g=#*NsQ%;O z^>%@xzd+x9sz}3TwsE<;0U-goryIBOCFF>7c(Rs`H?Bs;u`zc&Q`rgRfnd^4W$WLz zXHXJwpb#l8$V;_?+wRp5lFNMs3m9ds!y5B&dNo_1Q<1%o&$wXj4=KW@sX+?K0-_An zbiq@<;Oi@%t3;g$BgRdDRoPTSE7WS`09w3tCZyyWCwa*XEx2|ouRZ@~5@oeDOS#H5 zW=5aq75&OcE@=dmN84(DGzaDz*mA8GP^Rmq+&!6EG7Ki)kZaaruIeO3Ht9C~L`c>V zg1dh%Yqv0c*RFuVbecjvZ4c%mi~^OAYe5i9Kn`s6kS1D@dM4?wdaysU9c#El6Bw4u%;O+|KRD;P^*KgVsBbHRyNr)xj{OaFK z!OXH@#sQ@6IDDeY49VvYTIfEzi>63_}4%UU_>W-XDCTc*0@KUjm92~{_nV2d+5aCHiKlN z*E72uufMw*s(Y1^j!SitD!5#V85-u_UBr=}Ol4lwRY5K61+m{(Q>U7RsjUzEbSGwe zSC{{N$I`Wm!mjR31b^QaVmw|>3IQR=iuTx)KX5f|UF}LvyGp3Z14QozqROU_-VUVx zA%Uf?c1ULr4+Ca;55ZVWM|1i((@G}<;kQ}y_Af>a+DCTIfyEA#pZ}#nXPUnp9ddsP za+H<%@>)R_COM%3wiJ~D}`FnjCn_M znU&3@B_IxVV7F{8*YRn4%GB~NGK#zoXVP7GX%$1mKVQIr#oZ-3?XoMW*cU{PvjQ9v zk6E6Noe@S(S%7x{e+21}aCV$YzSRH7tJ#}OVA6)x%+)&R8M@RoeZ5yB=6Y02cw+pa z|AAVk9El@NxzAB+;T*NL?2Z4ES|_Xu6;W$KfP`AF1*kPYd5&5$l8gs@{-M^q_}rsO z0JU}ms5Q+e0phv}fYu>Q5wxC_Sk{y@M=`bDPff`uLKK(~eF08`oZ#Ka%(n3TFVvd* z@6@`X0L}YFt&ff&o^E!PDArAYVolxS*@y|GAe$dL?Po}-Z2;#M{6VcX{|mLAw9fwg z2er=W+%ZS3KPU1&iK#X1fN7`Lu%_+%GystugnXxF&2Yuw+HB)OF}R-47lUhBuGp~7 znUomTAxT>-x9a-Acwb|S?NvOSl?@yC5gykv+sCCmBjdb)+YEv^aQ$oG7fRS? zV<%RuT~f2W2q4E-GNO%NM&VJ2*9`VE$o>WMr~RgU~m-Fk(5!JKVPXZ~YbGfDxA6IlG!T9pAT{!-iY1Jena zbl6jFb?R^78eeceB+o0om_R`eKLjTTWtqT?G7$E5WtMNNgBS39qN?OvmH&{g$+grz zsP7>1Z$P>RRW^s@{kwF{IazQI=w)X);zO;?a8(r>+v6cksdKBpF?HBO0$eS_h9kgP zBtR|=q%{kngcMYp093_3*)oLtzj)VFjA-(AG9B~n%i@}Ebt!|eDstU2uV3EvNUg({ zZ8Ly&%}4~aYp<9&?Rv7fJOuNHc1=C;EM|^f!?$vmgGKE6_}{KIPIKtGclHugF{2b< z*93rF3lk4drY)oVV%PXUfL+@SmU}mFCG5IP%&zqScFivnv+D>6yDk&6YZnQ-=Eg1r z*mXtK9J_Wpz0dFL6PlP^v&HP1(?F20>)jzM0CvqeDPq_3rVdV3EL+U3KUIs^HMt&e zS@-$%ug*>&rdf7rFN)Ev9E6tn9O0K1lJN(sqR2aDM?-Ffkg+TZLt@K1J4Zgg4O zGQ_^TW|n;AHvh7Pgk48o{6Q;t{hM9W#q63MD`D4*f3s^)%d$Ry3A?^8X4g|9_4<+p zt!Npyu>C-m(EY!#>o339^}SQb*+0~4%Y*;0YqZZVcFh#A>n|ep`a(fv6~L}bB(H*{ZugahoF-jL#nu|iwDTPtSQ zoHOb^>Rtf4p5Jh*>%XAdfgpUkK{)ciPUQ|7eKwf;*|`j z*Td0p@j|#Jp~b<^$%n)OwXmQ#U*5McJ3Jmu9`MsKwq> z+IyvsfTpplOt3mL zWH60;p4o(s*8Ir@b}a+2YkJq=MIv^M0N6G6VL>fCr?_0guCKho{wTV1)HBE7Choy2gI!A= zFYMh_^4|K=dt+cf`oyf5UAG@DtX&4bb*ywbH7Aczbb|d9$}E-L5-VZX*8>Pn0K5Lg zO}1OK7+}|+U+kLuP{OV!Q_(NP?D`YHuJMsQH)9I<{Y>Ya+nL4Vi<2C=u>iYXBWBk> z)|+1vv+Fx9NR}rm$UwxdKNk+S-xRUyjW)m7HRZYK(~^3TdM#$xoD6wz{e^}n7gsyG zuYf5moR$8vyjG)mur<%(Zv1=_cyViV_ohM?~=f-ik zV(MrWxbZkI=&9bYD?7XwnjOzdM#~YEK;vK5-<<+(@H^# zj{)_1Y%!?0)_&}B%kl81fO`Ep$vY?S=MbP?7n%~(&b?V`{alWETZ_1f~oTR^?8dJU-8InS34MQnd3Rh;5OBK7+IvtohZ z%p={ifOv-9?k_u^s%8uxA6OXZqoNxcdjc;2cROa!n(Ja-L^N z>JhPFg2(%wU2%_-aee-LnhP(hn^YdhVXrMRy!_>XzkTEI!m{G2FTsTw*Q)C&*`)F% zr2Yf{sMo^f_sunrogD|_+6OWV6VYFmW*>JYXP*(9*AX89^Lj9#tZ$Y153b3pmks+{ z&JLV7d|Y`4@O>HH=7pLJggVV0$1Zr@C+A4=z0)SQYaEDczrC-&kM@HaKXv1v4G`Cc zEyU0>hM@eGZFRY^hu=+u@IBMtI)tL`G8(&Ra&@Q%CXS#xnc*K9>Vna=U-!~_BK}$k zy7`NC?RGz8uEEN!wPv0rUWGc2t~D9XWfa zh5D$Z8kNee!UZnbQb)>asHDr2rvPEuHoW%w2IEB6@50DsQh8aotf0D^q`dakzz?le z|L|&H-%5QkagWG-0g+TsYHH77c(yZd}>|!C-avQc6}nrH~(13r0q%b+_6;X z@M>>L?hiT(UMZ<)RrG~RvWXa z5bRM??L`JJt?>6$!AA&B!&N%HJTn%&EN!}_T|1tF?-f$gHDE8E-{l}_r)GraV2(^{s>yruR-rB@yIM;PvPGm9C!Uhe*ZYPFuVP?==9$ z-rTERu(d@guvw_2pJLh)rlpYLoArWjrUubUr8#MWQMukv@tdY>U(7y7$42ODjpRoQ zldmbbOsu>nRM^~Gmelqy zjw=(-&4#oem-+w-&8R8=E|8WoI~dTRp>TAK?e>VNoxaTxg6jLr&OKO=r*UhC>K!@q zzKX;P+L;|bgHf3QQ2ogn3Qy~(T~5J@{h)x8Zivv*8-RVysv#nP8R1KhHomV6viti} z@N7g4DY&`HfP!3|@)fz}{^#>l@q%#7!&N^WanHOLS0QZ6mh>Q&dwj`55^6)pV2`!N z3E6je#9toct(KBzTzv$b0T60DJ_PnEhnZvsnd^i)M3>vfqWBulz0Vz1Fq1Ug zdXp4*C12B1P1LEiuFtksIF^yRu7vkOoa*lb0&3a}G2DB-MKAgwq&o|>Mdr%dKr5Ne z-Jl798QrX#8pZ2QAd*)yA~d(gQF|5-60)xbNv%D@Go)&{AZ_@(wG|#UusTr(|@m^y=HQ2dq5Iu0@8rO3sG6^LByaA5Q*;C`_dXw7>oRhj)^m zvK{tYZ(cq(A)K>y3z(S-ObD|d-dSYz9A;E6Sb+;}{N3t}Xw z_`*mD@>Xk@4lZ2QB6c1jbHMOByDODQB!{>2wnS-?ZM(izu6%Sl95@?ITM(hBXSXJJ zXh15xk*+1z-myY@Z0#M9fc@A@2DY_b4q|DlK11$#0JOmrIPZDPgUnB*Jz2=9O6#Bd z6D*}!$UBy%pc#RagVUhK{(j9amAyyeli4z_%Wi8V32#gM>&mnlp0h(s&r#}>bFanh z>lGp$&LnVAf$`qfeo$yM2CK?RE^P$}h3D+_Ed3ft>V07yU zmcmXE9=#7i1!}8)+P+96U{jkE@fG-|HbV*aud2!FTQ^NYvrg!mN>8=toypd><*$dO zvH$^_die7RK)|jzt;X0QdlsZ55wP1=9pHsk0RpzevCm=wyHsC}V4kQ(>ljU>pF1WN zunB9lQ&R6LCbtz{IUv{s2-x|6fbA9ofBvSk#{lrJY1(jqCsV+`cG?)*6cN<~SJ}({ zxJM%;MTT?7A&TSF{hAW$m6BwhD!5L=RzMG>ZZL@=N6!MIa*SDHadW$4&t2it`w_7`4Sei2ry%1!yY~#1{=U5+=rz&yk4ERRld%Jdc z3*c?<+o>)5!0qE86}hg2-qEFL-4X4D5w$EY&;$YQnoUR>U|H73eNh|dpcg)GyHZ0- z{rn{aY*k~sxiu$!FY<4=js04eg+3_@T021r)Vt~vrMdKVbW>co-eY8Ld>AQSCy0H) z{#LomHGhj16|U6g!+u+vnY?Wr>S1^sKk@L_1Y`xTvmNU$E2DFd{1dpF5yOK)HNv_~ z^wRWaUW{X=ongQdAZ4ay)A?^N@HFDK6xVb2{m*gO{3~B+Kj&QkUDp-R29TX?LHE< z!z19W3NRKNUH|$#FcwTcb^Ok`augH8m5TKQ>-Cja+G@zuWNJmn$LS}XyK(K%*plWZ zraJFhTPPBCjtL(#bZII7+C)v@nSI$0Ho!Y5dvjl1GPJ~?{y)&K=NE%>yW?){7l7Op zUNRk>=NE(L7lZ$GG1$xOBz_SBl{Ns3ZSB&#WP=%ul5u}#IKDgig{@|NTh3+yBUQ7W zgzA)@?wq&@`ukuT4+fGJ$ZDA-STlFn5v_^2omNfOfjbq_Xi4BBZdz9-=t}~r>wR+{ zH4zq%E$g9z;hThs>nI%AZyx2C)rHx*Q;zWuyjGxP0`-v1PIBHPFw~8cxb8lc;0sI& z&;IA8a1$E=4fJqT@M@QOHnsADOn%EmX9#{duM0+t#wr9SfG?sF4R@HU7?DPHReeH& zcC`}^O?}wsTVH0JPwTQj!+?BeBF6Lu3p-(L0qNhV3v?n6d-=5G=vRg6k_4%1>QBQ8 zwQ|<)+EuV2|9!-r7d>DqInCqyME*s*&NZ2rCl|p(5X7l&MLk*<8dRD67cCJy0W1-R z|LYQQs>C-7M>Qvx8s#jPH!LR+ z?VN4S@mVqh*q!9TLWeAuv~=Zo*$Xy3mbIyf^#?1J62e`V`T%l97KapB=oq9=GlkP` zhc0(?RJC=y;Sk(Wb+Zs|v1;h9q1Og+4*Yw!lxqD)S5XdJpy;3qYanTd*O(hWXC2Uo zDqR;ik<%xn5SdX)N2b~>P(|2ct?FXeZL|wPW)KBmM+BD9xq733=}}XzzQ0D-zB5h3 z`pj)_@}0J~3=wv&DEH@g8T4vqA_FZIlz9o*I99U#A`r|h7PkK@D*?!Qq1H0tv=Kb~ zvMCf&RhY7IFa(U9brGo6p^W8^@Ii6JNv@Fr@kO;O*x~+>^p!N2B5cDTlHmkZ79`rm z`2{Gf(!yMu0?BxgkEk3p!W!y3s=BrL0CyQ+O_U@=6@PfhO%ZXeFy4L}=jhnC7jPr- ziZWnKkJKB4QO$|q^)Z2aQT(J2ko)*}doKtvlIfhViiPDJdyWqhZZ?Z4787y)tHh0? zIdlmT50#n;`|BtRxE<(`AipUy!2|?`*LgTOJ2NmyokF>f`esqJLhO@9w%DCE-8bh> zyDIEyb=nH_#C5yt5$BAb{ACdUxYO><4@XC`|CnSZS86}52APS8Un;lT?*p)u-^zF$Q6I#|TL)xUBfm*yyX8eP-tMfQaQLbI`PTt8d<{dw*DWq5-s11O0sIA~w(Rrm=jx6;NoF#U08DfQIjKzA zpAt2~cb!s}nw+gkIe2sGqqUZTj&_JkPXvaQeu@t}N#@oi^(T3p9lo@6WfD0$p+L$7 zG+<=6!RRFcoabzX4`w^cpS?4_>wU+L2WvbhG5b45Hmy7^V&94N8^!FqMOS|F(gf+P zOc(~#uJnPNlGFcO%3*nke2oxsa6>bAlH}_A$&6*?vT=!rU76R_4ep()FYs3S?j<*F zIMEBqcuIKkF*RYbPCs1;+z_!d1-72Ua>ZNEN0&{}bR0GIGS0#yG^GstwWMV%lXl)7 zyzy7Hs0I!p{Lo7ey3m{*f^yMQ4oQa#Suxl&_nq;uhp-%W5_jn0!t9w+mWA#A%DKGJ~> zTE|mqrmQ0faI4GZ%9_=F2f;@R&@I1cb@mvd-hGZ%p8{w#$R3{x-_74?1US}QGX+rW zpF!}xUbSVPbbVZc=4#-Ktg*r@Nex^DsDTST{0m^aneb^Q{JgHyt2`Z%V9iW6>;##1 zppt|!V*?NrfU3ENXV{+a0LR+T9XP)S9P8K7St7@pn6Q zysd>)E}3uU?^aca5tYDa>FnQvHB};5Gf9mD=}RU+*8x;botNQtnrH%YAUF3{3M!n++bmXShFTeG;8u- z|7h0q%nx1a=YSqKS*t4nKJvQ>_qu~#Kd?`w;n$XPap0Ajr z)y&v`Xtkikb;t^!)o>0u5k*Xg%xTsez86R|>wGzBqpd2&N>#^|z|KRsKP_vVZ8cz7 zZ=2P3wRe))&0+`l#<0ExY!!{ydS{n}lrgfE*tu&erd(1t9FFwJf z+9Wf;4Qy*91?dxWI_?bw&4#OV9H0G8)J4gf685bRGi*&4cfvvSOF#|R-r)8McRU4} z`%7B%3kP7T-ZnvW*czJDiu1-znt8-Nf+9hR%A=Y)gOBuyTHzWZ*;)*&@muo~Fj8zv zfwia=zElFN*)h`LhRDZ9i`~rOKl8a84!Vl}Ass{FbfHc!^r!O@oEMWox?wl@i%{p%_?? z)*;cAjj3(9>I5H=Y)y4G_ZI={Dsd`&#h<{M+pzS63mSiqK*y}Dl6Mu4Knq$$Bhch)zzB4iH#Bn)7JvQn z4_c%Ae~v)&%H~F(`K>XWYmyP@C0uAL;7RvmmvA74T&x9^ck40s1sN7bmYLiJ9uZze z^RfHAZ5+QFHRU*t^9U-tNsJPUlg=RC_lqLgntbhEBsi7|DxkM70D!gN;u>1_rs+li zST6;DHKSFQ!@YV55()roAvewwV=`#@>fLF8HtUklDA}nyie2lC+eEyYI@_wgqOU8^ zNQSL?eFPYRW^a{@KyUHsiJ|&r0j9N?x+5?Gjfc$$jbq1g1tpEEC9QBFR|Kr7J+23N z+wHE8UsP|E0Bia+wegDpu>R&H0@mbzZH3#&_d4V{0>HX`$m%hT*X+}?Ww_%{VEwlB z)^mm!STlILBgDX3cr6Y9*6d~(eXUzQG55s4`r)*;23?d2KLh}4LF4fsH}UH`X_Py} zrQL*Ow`EkCQ~_X(?@Qi|u#tnEBJrs-L-=-;#=@JO{KB-$*mLh%71iz$uvhuBr|y6N zVEtz(J=Su8`2TAxgU#* zD(i`Out9L=VdDdNKZR!go8PECDjY; zKs(w>7d@HVf!=r;J_LefF|rDIPeeP=%q(CB`s3HfBPr;fVJl2g|M53#9Z0ZRAQUdZ z!Pul{O}NiX%^StQy2}L_?TMnL9RYy#8`AJ4F|b~nmK7{%h4TdZz9lCBV9mYU49M2x z40+b67R|@aW`^b#7JP$&Ef1}r_!s1~tSFkmgo?_j#SZZ>P|nEP)ExEe0@RExW(#Hp zUuUt$Xx&fzBR_SYxM;0l6V8ji88*N26m~J?bzm@TWn7jC7iEc$dmH^~!)%=3nvbE9A9f@rA5;R2SsZ}!QMJ*s(Q^En+8ddwGbo;}G zEP}&bQnL(UDXS6ndB{N)nIv9=wgA?k0So#=lbs;%1n&vJtgW(g3dv$-Eqr_YU{>Rd zwtH12Fi@;Zznjr;HKWn=al<)a4Z09u)`IIB>acddm^J9Hs#db_X|U1N#J>QE+EUNl zmnR%m#{ji(edxn8vjDTE-+yE%c}MUB zkrh=3hG~4jwaK72a8dcfBTtS4Nq{w=r{2$+mNT+cxvyWCK|f8tmhnT((DF&sXA2M9 zt+J9{F!Lql@Z0PC$EOATD?Z|r%nV0?Vz}eyjGVSAcSQ5DzaOcHd}~FKZ(XbBKvU!76QKYD~qN0if>(jZ%ykt zbg{tu_@|F+V58AP=bsV*N8vj#211gQ)`87&(yx%-yBo5oMm_6TP{ zc-^n%g4KNTHET3Zp^7%r;gpJ8IHhuwzSbdgNMR2TSPT|9*86qR2%ReGx-0jNb8f#{ zaHv5#S2+6d*|JibJx?XTnvkR*0@nN_F|dBG<7JT>$l2$rX+E2=N`V{yN{SXp3Vw}+pb+p`Ll@%eeB@=+bN zf}LBH`&Tu+9|cm|+m$>NE1s+@*ROwV*{Z8PM2S?Nsj@>^F(~k*=9@bo=aYQ*- zL3baTHU9I*#i9b3WApO<_@k4f;CFjv-xtPaz5T$k_INzn7E2_(1sy_-x#2=RAT0ao z#=Gr=X`$Q}hupEIHsd(`&zny}c0+i_XmEne^T3aVSq|-0>*_Mcrs;4D}px!YQ4soa8jy7BAK9$wOIq?n;u!2S%PSTx|&k z!~9IU@^rsjh`PTi?nWy@8>E>VxYUrKE)23^0^t1-4H0_%1q}AsG3eL8z3DLQ6P6-rpV{98(?|jfd-SC0j zGl;(xQjjYZk;4*_q|l*1k#F+R8z$c7sgrMi-HUf>J8Sxl5T8$Pmu zZM1I9(i@U&IDNK7TfMd6EZmQAVxgSrbO`Lhp{IR_RQE>DdpLIu`cqg@k52YuYhk&SFXj~V$#}O45r%zM~eX8dU{Cb24aW( zlf)pvw|0!^gf9iJUEoDK&}PjGJKXKMm>K^;`fsC(Ui|)V`N*Z~w^mhmT>R3OQhLy% zyc*@je7x?SULAb5-K(zKh}1{A-o>-Ks1G(DN|ZkxEb*;5R;TZ4eCGZ12YhSoi=xG7 zf4ltx+Tmgdd5MB5jKbW)1B2Hu(EEZ-S|!UM-q_WZpcX|X_O}e3tbU#AdLIT(eHX84 zy>~WwL%u*JL^%k8bpnUnN#0?Zr*P)w0|+#6;htG*N0{uQC33}Xfr#C!q+$nf!E9fR z=}$cX^Uo&IHB+RV%Hglwu4s5=AiZpJnzN$wbWC$hiH#tfhPri=Qelr?9p_=yD9n+jQ zzH!0qj&}PXP*PAQK{Te&D#jnb@k{7D4F_Sj+X9B~~Y8%DF(G|JBhNGeRWzgB3hbg?NPB)ATHw^rB+{k0M z0Gv%+2|3!;A+KzfY}LP9y|?zBN;f~%=wL-?2rR@)4RMB1UNzjNBU_POgmBDe&V_w94;uLgk4&PVw_>j zSg(xI2m&F)M$iv*(LU+!mY?D)j0$^UAFGJazwOUSD=;0;Cqr5Jyv{?Z87U6En&z7RW9g6|Y4bEA*=Dib@ROZyZNV70QwlDz}p}vVvLr zOxq&e`^`{yJiz$_UP+qi!oXqT+TpOaWVHd6^B#8@!PQB>Yt&UM$hPSz+eStk+9Ew4 z+3tegnL67h#q9H2rf#ym_cCH;ECIRhPGL{!@Q|!W&yLG9IaAeDDoc27&J(uTLlEFPa^fk1{bZp9BhqyEOJSByGJy6p&>E!U~C`{TNbRevub4ca%@{>S2G`V z?>SoAj7LrkaJSi~LsAU90nOU-wYZ9`l*~(27&x818&CKs^W;6^Y3P~_2aAo#y~_G7 z8(10^ zcbq+-7v}xg$^oYzUm8#(W6kM;x97sC-rtCisj4#`=g0TtdM_Mc$`lG+2sP~q0Z|rk z@D)$HRjcy?4~`&TjOID?QJazZPaw6-KKK`KJn8%WZ&tuWw5<1j(L{9c1Emv>Wto`h zj2KU_c5yieqankX1J(^C*ABHTX##*X``Xn|Bp3kJEru?s<)0FGC2X@v09Xs`6;-$+ z>4xTWz#0RZ1sQ{Y&p}W%2!xsi&7xI3xSX~G#DUTQCbzsJ1+VQ@>M`*g$c6koajLhW zvL{qF@T1nd->McuUo^y)H-~{1_sow(htK!I z*D})slt?RgSDb%qY1>gJL`Wwl)^tZ@p7F?eg;V&@_jqBmZ-ff>RFAdvOX-yB;MFTK z={gf3*-_uQTn+q^$SP`>cH<@M9hvzFSM>HvS87*&2gfg1fOf$f{au31QqhG|D;7Pf z{~)cgyuR_ybm9_~c8@M*&VK8XmM)})`O>qzeTjE>-@Lt};M5At>fKOt!$7~q9LLV` zJ(bzJ4y1Is-3Eok_x%5*S{FdeJU(bI@f)out7K!x7@#xl_M2VK?`w5Gu!<{)bd>3>L%-TVoE(*ytm?-h*AftdHXVRju)YvcG)5@`jmv9 z`zZ%7qB6M9VSXffek6K+Bzk@%dVVB&ek6K+Bzk@%dVVB&ek6K+Bzk@%8ZedTN22FP zq5)HRek6K+Bzk@%dVVB&ek6K+Bzk@%dVVB&ek6K+Bzk@%`hV$2^gQ&P?`zMGM9)KC zRK`AZsOtXN5x%r~Jm0dhAzssBpY0(Kc>yu%i9%wE^E;)S6h27}4%%Bt=A`@8wT#RR zuYxQ)R%2?@aKnsWZTV*61t_$0WQ?-+Qazl3Aol(RZ09%_{+HQiPRG&@4CUtX!DbH- z^(1XYc2<9|Dvf)3gMf_f?LhadZ@w6p@3h^QL)F`F{d;rSgVeq9Z8qyaa@F3VTy^ts z$nPEHN^Lxi-y0UZL#zUWdVtCi&TSt0&O_gM=sOR6=b`UB^qq&k^U!x5`p!e&dFVS2 zeJ=rd>ORr5a_Ajm+kxg;5RCmD=u=-gxHUh9=2cHYzZ-W9qL=I0h=!FlUSgAq8h<#a zU+c%oy)u}zy;nZES>?U8tx0_YMMhWLrgn_Av18v2;N91#f-k40=LsB7updI%P8Fox zk~}ptfY7>G;j3IN!fw%(H$a~H?%cF8_m(72%}Pawi1XC(K%Sbt6zF2_NkK1@wyv7$ z>>luYpa`=BgkScR)H_Rma33wMOmtzxmoPn|$T^AJtWRU;3`(lI+I>6P-LLwobG9#K z@a#`VV^N;^oM>8^lPGUibs^^g(cQ^y!%^h1b@R{{YO!M;`p!e&dFVS2ednR?JoKH1 zzVpy`9{SEh-~Xl1_y6Tl<@{qFdAnSgX1(_0=?@W(kgZkOr7DRbAbw>EF~l}M-DC>1 zA+gX=|6pJj!V`K3W&d_8r=z_$Gy2naZ$HFng4|w{PPrTRkH^RUC>2(61U?9zk*~pr z_3NomS{1$@EKcrB7`>gQ@cH78M)y9@i~^a}^r~G@rQHB>R87}#ApTh8XOiAPRg&hh z{*KOR-|^I@(oTELt=5a5ZYfQLougD~%K^}r>^8p8fLZ<6VPN*Pd+1+lbr7HH{@&LH zKAwBaoEOsZI_IZFgupKD>HfAS#PuGDL+~5h8=lyo(R`5SusLFN$@a{mo>HXJxkWcE z*7-n}A(ZqVsj6=2j1r`3+y6_N8vNP9V>336yB=2k-a>Xk(;dsFp}H@-pY5JJt)-Rb zp;x40Jnd@r1nmP_?PjZOL(4^C4SBcsHoq+Nw<9I(;)FW5rIJ+g!$97Md@ida$E(|5 z)XJZBCl z=?^s5I^f0w2Go#FT{YYFVFqvN>b06NGCnf17mHI%vr+=l3gja)ZYkUUPK`cU@!kJa zr`LDXT87T!(Nu?#W*pdty!dVE7Wfi%jN|9P@#fP{+iD7bPkJ+k@BRjmL4e*1Br5_F}YafA}^-yoB={*@o=Un%I5EA>QH+3|w zP*f{^X=ZV9NkWh8$#oVEg1dVuE41=2-@d86W1_9!`-X~8tz78S)b#jyT|oPTVO}O? z747|Id}P?on##vd{UYy}TSN=YW?GYpR~dz~_m(>haUDk#2G6~3-tNBd-Iu#WcDl|w z&otIYCBx|_IHN7(i(R);%nwK9uG(-j+ERDt1=k^DR7!ri{qeTUS8C^^66G}g@hQ(O z7MPwqdd#1Fc<8ZT#bJfb`2w8tk}DAddsCu>R=UVC0tQZ0<^M`k51RsMYQrHQO?^UytLK*e@IiO0%>Y0kfwJ3ou)2w(-KR+wDrFEqyLvQ^~3+3rVcLw($vBW8{a#F zX9}ggWjC>IYr1(y7A9Gccz(9lTM`y8|3+0!*F*={`X^m1?B2eq+C-MjH+VRmEZaZT<6nnQ z(k4+=X&fE{;H{uRKX63bZrE8{IP*X+nCd~q9Djmxl)hOQ$*El=mh-U?G;Y{gsn-Lc2=UAOi^8ljs_#^+_UnzfPc(aI7nIQYAf3QvU>1cl zwRwh6q>B^wOK*b7gqiPjXJl+JBu(Z+p?O@5mZHqDcvD|TnGiccV*?+g9wC&nn92c@ z*>ALan{cZA0w{F=V$76H(I4KUgeP~|nck3*nhhsIMrld(Q#FYQVFx>P{dGIai1k)K z9&YdHP-HyzE?%tEzy{SxI+h zY_?8Rm{}uzyqYU(&P$B4i5%Q-90-*XCZOvFAk^mEaawjxV`ViOdUqW4cB0XCXebmzRF1*8JHsF#Yl|{XYqehyO5vkc+!I!53xD1IylAf$57i&}vYU3ak`IcX5>W z#luxSo`3^66&eH9JpHT8RZ7&LOK04gqw@HfI+cnVi#I|oxnQZUC#pc5$CTsfZHNl_ z%G(AnUu)zt;ijX5xOhf_`~zF@Q1a2HQcSVWZSNE^x-$BF!P;Z6C4siXe8e*ab(WQF zozB*on&hIt+bms6X%{J|#>NFZ!0tMb;VtV=UB-gJI1&#O4@$HgJG{zDnu>iryJNA! zOF!KAGBd$0A7c-PVHXRs|_(I z*go!CC`=%+?JNe=~+F3#DE zY}G`YQx4i!1Cz))>+()$F&%`0@s1QN^mi`wpb1@S4J||=gvm9C%kcdRVyTghz*vuFdZS~oUxjL|wTrSn1LVUG8m$IF1E}yxDx4xf-k`@CNfwfsLBL?} zwa$IdSHa(LP@ZhqVm|1Z08z0IYl%l%#zV>R1REB3YSH4ge6kJ|yhb-BWi#X~9hpW) z11rt9EZ}cB;A2i;-*dQZI(QqEwcGO7P&32p&k5zQherM{a6p|}Wu>@IEfm$MLnU=; zauSahcl%eJdO%XAW_mrMyJd^()G9!on(NJ)beSRVHk?o!M2hRw@dThwoi*Fyry#CV zyR`gMr^eUlJRS9@0qWG8KkC%9bwBXn89ZnSVe4ZSv{`_YVZcu^;xh3QqzKTBo8N$V*y*rv(2I{Wz`MfJAZB|-^m=Fu&^OOjTfm{Gr-3wh$0Sd zd?4$CWJ{T6W*|VY!}dtFlmqE&wF2xtwU9GH_|_UHY2l(w8jAZU%Y@H1;ozQ*;fl}M zFJKcFZIYsrWf0t~aSwQr5CP<#i>Pqi^{i1gI)_Gd)~7dbLSE>~R^}&X5HKg2)N}+m z>g;Gp%(S$fqT^!Ev3Q5fb6}6<51OkC-Q1-tCsw;s&HCGgp9@r*i38Q6HpeH9BF>D>1**>nrdLqQbCn8z2dWQszn1tQr<4crx{ti?h{iJYA9H=h(@+(ly{v%LLF7^CA7pNA^ zDL3c`^rgB9u$yfQC4uUra?%U8s+g^*s#F5I|7)OHZZ<|#sNQbvZtF(^0@cC40@a5v zRoXH0W68&XK($efikT!(4O;R$P`ziXI8a?~KEnk9)$3*$NLvMCeL*@&6a0h<9j2We z5+Y~Vn4?h448>fZmQffk<$&LrikFt5VxnwM{p4b4Ov2tz;29oF)TkC3P45Ej3jr5^ z;BHjuTTS9dHU4Z3J}lV0xX!Q;XjC677B#9>fkrjOxJX&SAjBPLRGW-Zh_os*InmTAzvCMNB zyGh-Zr&Mz&J;GBd_sXOH7*%fEDr!_;Q2J+7+3E6JqZ$}IUho|Ez7C0j0*lsp>Y8(n zYKy#o8rATs*40;lRZopn{i|i0B?hpV1#ipB=Lph&|&$LAW=lq)eH-an0M zMu+w9Mm2|b|5u}W3TRZ*t^tkeL)&azm5n8hYSrDOy_YR&ok3l{MwRCp)x36--=oUw znt(>Nvt(2m)X*UrRi-t>dtw%SvwXKiJgUq*qhY7+Iyb6(LlmiYYgJ!m*d1&nbM&CN zQO(=Bzg;Vq3)xxU6GQXKl{Bhh`l3cP-b6I2{G)M=q)|%9L zrY#;-o~;u#sx|+$QEj_tu2J3d-Rdz{JgRK>Ka48#e~l{Bc=6&rFsh9Ik5Od=(5Nn76p6<; z(jY~}qDJ+^JIiwsVBFHuF0;6Uf&T2@gCO zp6@M-V$f^o)ni-yf~eAl~=18kxz#m-S5c{tM%(qiqqPmp?rD2hgJ{nI*j0C zLGZOdtV+0#G!4tg2K(19Md-wugsvxS43VO59;lJcyUoW=0Hez91^`SO%oL3(&x)w^ z-5I*d*seh$VKHftE0X|O-LHRU3L3-r1)z0=Nl_55hFAxO@*!o+lBe|JwJJrpZ}+Ad zL1kJOnw~I)@3_1CEsB9gHMMVO7Kl{ihZBm10{Fw7-(WZ!bnY6=*iul(AiLU1y-5zE zEA*BpECw3YGTVA5*H!_G%7>tk04BPXH@B!fo{ApXZd1?1y%#Mi@9bV02P`Td`oz9% zS9}eg=*Woy7L{kHptOmlKRC}U{4+$zn(haN0WF-#QnSe=JQZ+1v8x5R6G8qhiyq=4)m{-^rSBVgsP*ro%Hxtz<&nR$fKg>> z`{V0@QDtTl5U5rb2dc>({I(HmNWx+*((=sQUNl`4s7?rm(lg#Be8~EmCJIzX1h?Qk z2mcRycm5Cc6^AD3z#QV=1(~MyZ7OjOzV9uXFi+&*gi5`FzjiaxUXPV16(&x98(}zbFQ(Bc}+# zZl@ots(Rp&PH6oNRMQ5te*)EJY6p^qYzh)AySO@)Hg-V_RMVG%Y7FvK^~gG?XDerwWTVK4G_;LM7jooNmKPb?eN*KQ5g+EozMONQ7lc6lJ)FNuehf9)#s<-AAu_>g6z`e~Q`QO3MO z{_MTI|7llwS73eu2ERCqv3>JUBlS2^-ZZS3op(!So+e#mO@44Y6Jk&}%kB@ojb2RE z9enz*rp-movni~;_Kwaz;~l4=)2ZE_WkxoWW8ZuKFwWGGw$iyKNOQoPTt#nO;g&<|AnX;eG^_-R!8 z+Iajjs*S})HKk40zkJ!Kjw*l$EF0DD8aA&`D?cFZ+h^6X-v_>7ThIaSH59jQv>4#v-t-TJF-`YLj z)^g;BdjxxLOzz85Z#RJD>K6y6lB%l=SaKJIpzNlsS7+x5B2fIoy7al_dDv7ltVswmV#8j?!BcDcRI^eZL*)Fs>%c$L1y2p7#e!}s{xoy`RlBP z{ew09Ra+)WT^q{E>p&Cq;f`*O>b1%I41X=hHQ40tY(zTA5t#xdd03Tn7LR>i%1+ap zX|6_BT5vKw{{9$Mu;85j*o)Z+5b zBET`Hp<6-dXL_3m1B+?Mpm z>UqG(mU#j4T9-s}(PuZloIJ7X`JDXCKsqqP|EQst&T~2RtmCOpR`8RmV8T2<>&a9o zbCH;cUCIL+13r!`TPUyEc6IHYCV7~Gi)3ZNE(V`=I4KaTYPrQOp0nMQZJ$CMy@5h< zLYVtOky__9R{JVcI-HHnGLx=KvNEgz8ZxWV8$Tzly)=~*vmn29C@N($EJ|~24@*j@ z<${u~&y20B(Aw4G-fEq%w_dJNN68oXy8TnE9Q`B=LE#%EUh;?=a65G^+@q>S+mgWC ztXi{!W#849{WSk|<_)37)>F8m!@-VNt)qa#r!lQZj(;I%X?LJY&eg?6Vy3!E%v1yW zN~Fa~b=gm)`pnxKlwj#)r8=03n@m!Befj<|-Dy>}SgF4A{g+Zr3a5&d>PfR@rCLfP zs{g4}FRd9iS&HdT{-snq-4iR-{^v|Wqtmm=v5%6Wypjx2ou}i;pGx&s87Yr_bGg)I zr8@eTQVqBhbno*M_wRlTxF4uC)Q4&RQmW4`E7h;QCn>3YIg4;VbqpGL$7@aEx@D!h zZCR-%Z3}GurBv66m1;o4ds(SwrmS05s-ON+s(0^r=OtFE3&cvb?k}bK?A@9rh?+1( zUy24PF7Fg8)yz48SgD>211%aGdx(|lQx==R<-e8c$qnicNB*T$*K8Fl)jP#Xbz^Ib zq8BJ+msqKmzI%B-WdFgEWA2pX%`1K?)ub0AIm=45i}!D(`i)qrzIOU%n3)y~hCfX{ zw01ipdw=92W7Cn9zm)2iCo?t_pR@Xw*kN4U(WY*+kJ zs^cquD%FCIVx>CuDE3=T?p3i;U3z8#2-}x|hCN`^eh@3wabl%gYXi zdPA3y^KYeE@I>7@pkAz0(~N#8)%tgnyQG8D24+h%mE(UY)t(ByT9*!`2Ge$mRt%Pi zmFiltQk@?Z9Bm8wNJQ+%I81>OFrMhv~vQq8n8O;P3)tW=wcm1=S6 zvAZZ%syX){Wm89zmX&I9hQg#+sWv8v6x2RSeH;x4ExTqynpM{K{i#$}|5U2`MV%$d zkh`Agw|*(rd{o4AmX{U^p#Dp#mZr4D>=P^1Z54I+=PTmYzi>E;(`OGXE7fKXUo;IKQ_qfKh`lRon^t|=T!c47MPZ^nDi`p_6FATp7QzT5)+M&RX*czZ9W z(aOsc&gi+p_~+WSxZ`Lx?|GDF`J+64rYiP!u1043`8tL806HS|FQW5|zUZjMoi){K ze_mc6T)w;xv-ov+t!n>%WdttU8+UxE?tX5UeVeiz2Zh(TWD zLfPlUYy(w!A7F7C_l3gnhl4D-O)axuX}Ev$aL9z&1Xb#S=PHciV@d&4>aHc+P1#IW zvauX2*;xKlO?N0f(iOP~6-5OPt33h<3w5Gh_2p;`ijibvS;B4818XL7!HvmVZkqe( zn-AeYWa0TFTG#q1{v*vBGqq@%6XMhKCQvp3iw}fZNgYjf3g@4k?}QP_m44pbL+ZPp z@W2c7#5jT9@x-czdz5@^MGYUtzRg!SixeabRLXqsaYIPBZ3(w6;kG5*wuIZ3aN81Y zTf%KixNQlyE#bB$+_r?<#x!vy+%^QNE8(^!+_r?Y@70_aX{yO;8|A3vcKKNF(7&6uzU)dH0Saw%PqHk43ZVmshgIIcv zq7>%4;4!I;I?F#oC~SM|Ue;r!5|eq7x%K$N`&T?N^j6gC?B~uXZg*86k#iA5>AVN- zSmOy$GD>v$jEU#_8i;G9PBD=!r+!CDSBaMo(%ma$j^`hGdiAcS%aD(3kjMny9lVt$ zd>yQSxV#Z2)QwK#P(BshFFWjNIF*shnFve2H^LBe+XKJ2ZNT-Y4q{Vvt7KzYvau}L zSbpr|(M4OLo|&#brS9xVfNEwRAwTmF+x_FKrJboAAK;Pil5KDD!Zp zZw~7Ea-QDwo1$*(b0lozQf$?EzTV*!NEsV$!C+#KZY?~OTW;}ft^sROor&fLOG6?YgiBn@={Kl!7 zw0Zu^zPps0@(J}Rmh9x6g-=_)0~c34XJYp99ODg?PCIzCrY!IhG2KEpv$^KvzMxQW z$qy$PE_>^HN%WOOUrF?pL|;ktl|)}j^p!+kN%WOOUrF?pL|;ktWvu`t(YN$(yd?Tc zqOTGCC@Bh;1`+u3KmPB7k^p#xt{!d@}-g5npQ`UH&Ci~)!jTMj+ zFi>G(A#OWPK!W&vZf^MYJFI6@A%D?tCZwkgL^Za`GGR2^=tFsr3o3 zTwM+Du(D7;BnozmJG%H{GuZ1)o#~q9duD>OR#VesK*){JN%E0vjWC9kKG#{b+nr_b zv0C|MF!JUCffe5ZVhs7;-)PV2wEM_VZmWFW<_=KKu}Qf(s@kZw!_ulXpcre`^D*OR zxxRJxk#d91D~?*L%e0$#o%6W2!Go8(aKZPuw5`*c76A)8zVCp+RIvlwIU`6pQKs$c z4%BKwni3}kJmE|EGKom`HrROl=a4aA9V8^hlb45#M{a%_p{G3a9I|hlYk}rsXV;Up)BZn|UOD3AYh_-p$;VZG26^Dtukt<_ zZ!bb_%>r0=(n*zMBaERwRrTzM53klmyeABDrFIzoQKBz*V(--Ja01+#5-vYTe4&J` zgl&1-qLG+r0Ny#5cW71zvpL-m+eY(Zsmn8-raKu~Y`N+5UK?|Ro`So0H+Ns{fqFw$ z0CF2?c>)-Gzy0lNEElU-D8&B|bZnmwPRCiZ8c{ru?gQG&A{I0=dkxgcbW4tP9kq$M zF-6uHly>_Fpinmnx5AP$&pQ@i26dz$_TY>M8PW;i;7dPUoJwS>vkp|4v9UM=6h}@qCYv#- zGgXS|XKyEdnaG7CkET8srAarvKyNcBn6DJL3v^WctMW;Xw2ZiMCxJ8(q|5+i zO!N4CY5E@C^s|6Rp|*UQdna62=KvDKAhpHI)pQEXuqO#c7Ihl!w@X}00Y7{kG;4@h6bhs)~{A1gvXvURgTnk9oFM zvb(_N{++9e!kqxQi4Vx$=;%DPR0pE^g1lm{MHWQKs|Jf{~r)*0Vq2T7<;$wV)CHM$G%Oo_cJ!#!?PfuZS;YI~joOUBi^wxmpg?#g+&HW z-WvoVhK+tDbCQhxX>xat27S~fQ;cWx<{+ZZ>+1qx3U5TmLLt?m3PPr_d0v*MyOVNB zJJ^+dE4PTW!*gXGW(jL5$}kIa)R^3GYwimu$@NB6s6qH*^BNW`!I}GpcfC?|p+638 zR)rrwm0&_;+{!Bo&CA#yGx(CsWK}i!#lpt4HYSbX44W0bkMP-&7>>h z1z(z0PZI1~*xr*|^r8qd@dnvQ+iDvI_;YcmCboJ62WAV?j*TbdMN;p-AybQSkMZyZ zy!1g@q8vNqn3aqIJws&%gio}U5rW!RK~j1^>qO8-e44Ev>Jp3Kc~TZf1EPykOHQsE z0ziiVh)F)K0q_c>Bcf@?7x3s~J9925fST#zEq4Q5=I`lVy;*n(0O|{OiD1W`t&{a6 zD=P!XIC`k_&fCSiy;W2YhKXQy!aBdXUW-n=lLl@kDVK>rJ(qzWOq59nxR|k?&PaRb zL?jZh&xMxa==rR8-M>eBWnE(0B0&nwoI6X3@I?TT&VyZegG;2L#)UXz0NgO?{(>e4 zW6Cui1@I>g!{6Yt>Cjg+_OHp_B3Ws=zlvUQezrBdj7DaFuc5X-wtcc?7 zRU@mT1l=mK)aN0Un!)>cr(C)qc7yO|;RvjV-4>Y$>%g^%b}}D>{=L|HWdMrACs2jB z^}RBmDTYsUjP=>Ezvp^|?!V@Gi^OxilvVn`F$K|S2e#d>x!z4zJ%#}oPD_0ezrs+w z)e9K^s9I|pg{0A;UHAi=p$G*bFnuS_@|nJFaq-+^XbrDuvoi!KFl(cLx)O_cOXCDN zIrKa)66XXmh*9li1Fl?5U$2ur5>XV2P{gCN4*~~C1z*O&NH$E(DM$ESP982}$`5f& zHmrzI92H<<$)|1b6&mBXnL}&DL%oluj28vasT!Co8`etpexRjdGMKx51lJ5ep?<66 zm_??Jz?i6_pNp}Pla?W2vktGR6KVL6PR7&#DWf(fcj)oT zi!q81pJT8?7*`Hh24y`?2hEh&sd2#D1ZK*3^c#K94WYXlMcP8d>15}}Y`41}r$>{FvpTUQW9MUjSN7LDejg5UPf*wE~bS9f~`>ywuxM z4@XyX(jpVpD}5A2h+Q;C%cLSB3Q$czLpgA>26!w5GR(oKF%dPq3dj@C5V<~p*YJ>0 zk7Q%MDwlW%IxaE~s!H%T>5~!GSLg^z` z-<~T~HIvb$lzsP5HwZxY^Dxf4o5VxC8u!#!6418Csz>oxqKvRIBv9;5RntdsBX*15 zd3f45wNWH9-t3qdC0+FWka(!~=xI*iuc2O`!bTt!Kxx%E*5tMR%9Eb9vh$#WB&-qr z!jHG-UUD%*y;~e81wp=GDg#c%L$&z?;?Gi{~=g!@nzo~A_YHMd_?-1=c9Xi?VqkH!M5SlZuMiFt@8tf7ZadIAH1Pm|=m`FprD92l>-) zgW@*CG)ia3r$6QSosYtJCw@-!TA-|T-}u-vb8Whc6m6w`WSOklMhFW=n~irKc-$!7 zKYfWmKw{KEYB3NY%%%ob&O22q05815wdR@b^CT!P?Lt$S<+vm;dHtEvI(SVNs({?3 zUIW|nJ#BfTS44fqIgxbD0anak;L^%3)nwWp=+y1bk?mDhMvsZE42dUtnY~4w5T+-r zdVv}!g2Jqk>V7DmEnr~540ly;6|eLH?(&h5JA)mjkZsydd5dJ}qtezS3apric4~wT z0pJ{FLNW7RQ73Aaop3;idR`5K&{B#S*I>ohbp3tiMF^^3r+BD$RTlB(W!$4}tGI5^ z04^lm8NSyY;h~>W&PBYP=q>Jp#BED?JMnv^_w8PRhDDEfrMEP2d8L=Tg-{x!!fg!G z3A4C5dwVa;8X^*?6ek>7B0n&pAmZyVLp&6ODR{Swk8_*9e1^S+YtT<0B+11ClKb<;v!r>(t!gv~f;ZCZjy7$Oa87ejM z<*JwuD~BtqeoyprZ=XmEapu5LWp>FFrXLML;yqx7BCuYAF6=GhiC#$fy;#pKSkEA( zgUD7R*s(b7KO7>tF5jjR1{)pCjj%M)qoQiq4rx#=^PYI3H`I<*jIS6HqHH*W^PQ;4 zwBajDT23-hg4#wftdV$cNdH6B^Mg(er}RMmqASO0FiIa_mO@xL2{mNmdPDG%2+}$6 z6`b)7=jXD@oAHWriLXNe8;*76oCne99p|ABTF-dTU%;Ic{B^;+l`)X9apigpVfItf zEUG;E?(J|ZY1o;uNQ=Sx^*IZIYbJ~MWFNyR@jmbLNM_!}a963qzVXfD{o;MzFMYVJ z%p$;>U`Ksrw2EUEWH-9;`rE{!pr#iL#2aR50`jw zRcce|y#x9_vJaeGmUR92CKv`wJosgnwyII?GyKL z#p>R&X0K}WjjtZ;l=THy1*xnHdds?u&~1WQGJ0*H-~)_n>I0xDcvkZB#FCHrbCn=g zlVzj`0sY)#5YZhhofag5#vyy=1mKu5$Hdv8V*^j-n1nl94iKs5WPILrezDSEKHRv^ z?2s`umOfEVf#GSxz~4{G1)x4mS}P2MJ%OA2NVVVIGfvp^_eZ=oi*#$r{#lQs-IIfN z1IrEP*J70_?C@mfoxT@=Bvil!oV}W;00863Daz>yx{K5s4D6&LlAA+7yAw+5S8iom z%Pz@L*%)uLRpnE+X`RTxn6hbQN5y6NX6=uNZVDV@Mqwo_QvktExj z+Q#PVFIQb~Adw&A&UBA?4vv3xR|$upaCyZ61gDKFcCjz^T!A&!nCc%vE(Ht^0e$b_ z{c%r*9PE&)f4U8_6L!BGH1#DEX#YKr@3rrv{`gEbczz{7`GFOMX+;(>Ki|9laQ^1s z?ibWWmd&H@rj%tzWVUq)x4my?zbk)+P9gD74KE)wagihdT(!jb5xzDZg*&}s4sYsX z7;@3Ht@HNUb$}oGujnR+{kaJbOfN4ozQ_bjN zIHVJFKe7G$M_sZN>L(w&rR3d0FD{&!-STLBU7-rV>}tLUg(btp^UL_hZ>Vw#At&~@ z8;9P~QcLg{&^lD-f>8Z(M#dmt$D>a7_KZmJeAi94qx4tft2dtKU)Y9J7rE*11FDHO z1A-%d!^{>p?Ka`y=*GujpUStKbDFAH5=Cx6?%v7=r{cZad?{2%dT>JX!eN{Bp>;-U zlUt?=e-p59Z9zAMDWv*Zz*rppZ|6Fa_neGGUdu`6@&{n z*a+-6rIUGo{`thLYfbvwnGkS|4RcUyb+f&-wk_=LSX!gT0}r10mAy2N3I+4H9P9lv z?{*cO;LHbK1ALANq3kk!mQBxSaj+CBNY+RX!*PG8cQtcRkrhJjw9Y@hkCS!Nd^Gg@%oH(*DMzq5f#S-yhq?h7W_#^@X`9%BE2 z*PsIQtrq&WI`8z`FG{(hU04;}_bYB4IX#J*4nnIO5E3?9uwBT$kv5iBQH~b8>AMhfbK36&hDm`#A zzqX|T{iPCUJbY=#$Ezy^90S)V_9*MP`ef%H!n-#wJwHhPs+ZE%eH&nkKfNwYA1Zd2 z(KUDzE#<~fS_RcmuT?RK6rArQc^@!eijdv#;3^|KccItl&|ozRc<1bSC0rJN`boF? zM(0bE;=!a`kKp4n5gmur*8-Xa=&iJxFRHT&33CNty1BQ!hffJyJvzqmn*zARNyjxI z`b_N1dPkur5{fLA$E!Zi!@B5*>c&;i*j7fiQV>!xij zkVET$<$usq7H5lYs#-v_Qbm+^MCwwG-+Rh2`6&uKS~C+gKsh=Qy+K==#G7J+34|#g z7=M)d_B9V8(_apyr>7ZNgh(IY71-8sDisEWn9%SpdHepgf0+Py1yGmj*R)PyEhR~T znnDuMR#>F?WQWHN;sCSGOl~5c%;m{9BW$3=Bza;0)4`d`GUuHjWLp=MEcB$y$q6kw z^n;W&>6-DgZlMRHgFve6486W)t)n1z3j&#$5Dk_s8O*b1DnMMNE-p{*y48t4?NgXq zM>PvuMn`Z_2)*^H!JxyA0j+Qna^3rAro(Pt_3H3Wd~|zd3s{IVok`kZo8PUP8FMda zdLLqnIM#{cSL-c>gYXK)@QwvmS^|B_ktK3lT^UffO(r*c=V^$#G%sz6rXS6U4hLSjNAf$Uu^(Uq#PXLyQzO6zh<$8atgW7Cfc$+s|gavGMG zwd8h))3N>QmwPR302FZQ+FrFqMs3zfRiWA`!t2=3qfg<4V}fq=ZTASzK5DKion|@& zW;mq;o0mmAb|VF*!C&n(NIBGwKd2Rzlty@a63s+>E4ycx5e~ULSI2Ug6N0vcvyKfN zZVJ*BC9Xa~)!Bxqv^v7XJRD)QU#{uYvA>*AXHY9819Ensy`$r*69OL+9yorKo3x@O z1@2$vs0kfRgT0{N0zSJM67TgWW=F0q3;kPmD1=FMc2=?P#6z`YveDzOLH-3?cVD)& z6U7;w|D=0O`KHl_DN>tV*-whQj-?5INjs9_}>lnnMOyw(&O3*&4s1z_S)U#h(Pp zQX+K1T%G0ahwgzbYJ#Qd6e4_8-Q2=7s>MDy*$a{3uwWRpj#af8c*lg42UKASBhros zu88a!!JR##Wa#lZ5i`j|ZjjS-uyuEN=S#kt-vx2e%DAnUAevk`S1sM2&4u~)Z`&{h zfnLuqFZUY7!Lvmh0%;({_ghYvzSRZf+r2mX;!R=$E_$kR5V%ZHazf!KzuXF$p}Uu* zen>g(eRwNOL1^#%e)pprR!B?DS+D_VuB=*m>^ofn4`_aeA|+MxIEF3pi)$L&Vh0Va zEtb~R?ADF)conSc&m5>*B(}ZO9;-b4c0-eb&6M^Ye&zd$72ud*duR>UsD4G2u5pY$ zbfmiZ#kE+s>Kz|Dd%SGSc9hrigVqO$KLZYZxUP40eYwOhZv3CFnhv|Jnh^dwRTEfR z;{7+OrrBG?%`Ym3JvjBUPjvN;tdSZTSYel-O3L1%s&>b_s1inK8tUZM!BrEl zN12HW#%A$rJu--fbxW%f`h3gPJ>O{Gy^K@s6GAA1U}L7a7t@NVv9)W$qlR)JzEXyx zzHl4Ppn&UNkhVq8sK`;qx@@qi$)nG1pv}KhCdP8gb_A&0L=R=`vQAd;H+WoteY?>V zvTki$zLXJB9=yN5#ib3pDM#~B8s@DU3xk{I66XlTCwZ_-8$l|wX6fgH zJ_7F;R3x?^XVTcJkvhwiZHo0$rHx8|8EtUm^b|XBN26Y+Cu#JdtT$OxTvA|45s!dO@&Oy$*v5-kzYUB9YrgtAT_tUT_i=-Ask(=e+a6|Ac1m~Gjr}qQV zbFzILOkrpWorC=!&5Z$-?ZH+HnvjwsDD2>5w`OL(Y_S1T=C%86%|{~E>eEj&+Jtb& zlP#GJcP+51JNW73d|ATy9u41QJks>8-{El1M!EJ8d-Y(JW%0~u&pwuSLd4p-LwJU{ zf6}RE0QQjTLAD&%rEPK?dfdWS>iVp%>yduk6YZfiQwsw-x_wuSM=WGo!OJjn6V!7-1Tffu+bj$#uaL zcmS89pMb3fh46768cdB|uSbSl{2%H^`oOAemlaWY$Ow0B*)2Tx#&6RyHQ7_Tm-u{` zy;-W~(5 z+t@wv<{mPDpityUX@F*?R$AxYz!>CGk`hRVk>e?ZKwaoA(=C*PTewvS5(#>(0+U4F z%1f#dc6VNnA3-*+4>{`Zzj*12)bYMx={Zh^4oQGhk7mQ4ir{+8ZF_5>!lI8vz^cWk zYe0c73qGC%?TTOH+r>v_)1#rr98lUH!Xp|8#|(BFEH-Gr;^HjJwoZuLTyrW-iq~N; zWw*69{1hSVnf856QEJ5T#1D_tlMEBh;HevdKM!kUz~*l9aTG+1j0pI+lY0cKGlFd7 zUXx$1sgj*+7!0FbeyozUZXbn-C5QVs`0+hWh+y3C8#m*(Hy6-uBn1Vb^EnTuEqo?P zDTy(wVGaU4?=-^{?!U3*T})QS?2YZOa<6?-!G`wJIG}VuRnh;0tH5UAiGF%Yxb-w> z+=Qc1C(trxB3qzR+ppLsvj`(>Opq+Pn}4i$9F@sMD2R}$j5YiF4fGix1wq_Jh2ODE z@gK1)@7Z!JGujbBj07lreU)^=axCK{{5zJpY*E2ZFr!w(Py92M3FGsRB9jK3*XA*) zT-YB;;4(JBNFe1)bhRZ%#q*A(3W1qjD%dTg1v(lbWv#{q9C#Q72CSB{-ir50_kREAGw z{5zFBO8K*8%OV~O@aw(J3OIV+mO`%XMoj}_swV-6|7!fnfb>fpi zqoOTENvI_jEYVfHO@!>OfmyI&V{|$>)o^5#N$NNArmp^Bo^jMH>m@1oD z!YVLNJbw%_8K_vq0U_X?a5bR3M4PeMD@-kz&;ysXFesNH zrR%q9dpj6PR&J&Mv6Q@64%|ZAZ3Lin3QCBesc|qzN?^I)rDK(HW7#lMk%r$@+&Z^R zc`9+PV`X|07<&{-&8TB$gb1+RmIJ%a{*E9!bm zm-~NavL(*3-<=F7iRG34>SQ)t$PIGEOfSZU12*JhEa+u<&oN^pXc!6G8UY$5l_CWg zo0v6Ned9}!K?ObpwNRpYuLWF)gEG=X)?nR4kXEFwq5uwMASX-8X#z}e2~7WV)#pJB zO;j;PLuVR*9{Q&n(W;PaV4%*SM#Nwwov!X7X#0Tc+Ru!SFkA7M7mWNKB&>+Uc|R@F zEUHvC!1@K&j*>t!43IMYXDQ=Vt!{v){-cz|>F*GivcTs#ze^eA#BwQPRKrh~kz;GG zeXC(M{48b6(!Z2WiA&kd;u8)_`0(=ooXQvtmJ_Yu0Cu`Km37yjTYa}`>H9xYnV_Lb z8Qb8ooXUD5s$(0LQyIVBL7d8r3_^8f>Oni}7saKFQuDi%;S0s3?34bfsTv>bKOZajr+j;tDDWgPmp`hmy8?~lzWggP=orS}UqP+SGGaeVJ*Oa_8EHhye zjAY@Jc&M%*<~OhMm6cF z0bx>pt5lZt_Gn~)Akn5~eIP~JP*^_9#q8r^J|Zh@IqN?y6*i}k&rp0`GO#B~Z3 zB5$@MO@O9Fn#z<`tK3Ma_$z|GS+YL4vYi+mOZI3aBlX`=1Mw+4Rs$wNq{cYr)~-|Y zo%7G21n2U>kV*3xw2K+BFE< z@vQ=V+{dPp20rdbu-~ch^>Mb-TJ!G{xK3Ux69V>QB5yD+1#&PXA>v^w^31U{jZB>2 zt5g%)E|3gNrXsUY*6*LzNyB~CD?p_-6SgnWE7SY!<{8&5FGo1DVKxl+L-@nVz(MN? zWEOs3((n~qe47n?Ul1M9L_(E|ZoHePhM&jX5f-&h%Tl=!^3!Qoe6IR5mwc~ zLTZq-6KZq_WgA2_;?8>MeYduBn2-Ul_gx#Vw~dd;Z89dvCEvD#+*!P&hFJrt#G{^b z0LrlbgbOrQ*z|nK3GvPqW(k1%(blQtTYI)a_q|5Wa`u8L2Dc&MtsojCNQkV$_XT&MyRr$C4*E*L*+sUW#TfK~ zw9cXjSchY-ZFEinff|o9!uBZ2naSkRdVEIMJq?{#W14GDI+8?t z?dw3Vjql?5SoGy=prwzxwI;9>Ry8benSnmM12QSI{vy+fW3ALZcc!cTBvpmp$+=0w zxb0qgQPhl#Zh zZT+AR&$ekLfn$;$Va?WTQsM8~ZMpw`8`e`j%IjHL%Qa6G*C9%KtTW=_X2{ZeeLenJ zSt`-H@{Fu`Pd5!*Fra@Fcs5QQ$cSAtL_tIvqg2yURee)P14cJ#ylqv@wG)oK$zwk4bIbFdnwYR!% zJuI$eS%GchS{7957{04F)}m{UoU}KKu*HB-c4F&+&!AkvgTwD~uzJu~!IR}$#_N6K z)g`WFm$x0Rhk-t4;U4~=>NK{EHwQm`xm?T6Ubwv+%R1YsXAEDi!7iP#!*lkZx49>d zWe$xvow!%av5b8X^lh*7kL6hQPytzVg7C?eaJ+6gmd*b79m^7}TWItFaV#r*-y@D? zO46V`o?ST?+;Bhk>QRqBj6SyW1J0rUrK>EwW6Y+*w^H$R&m07-&BiNFHYz% ztbo7dhtlNCEOtam4J+;0%JX;|6;wpdDQm>k8twbCgx*rPt)l?Xi%rG|q;4O2uO)A` zMwz7k!~Bx!fCFxf8LV7(XAk7vPRJC-y2j{jbd%gX%7ZZad7@?AcwwnTZH zdlcPl1qV0cdmp_+l>%TA33c;kVZ`dB}Eyh-4UXv?s^yazNka7>K`5vsO9D%zdnVm_%6 z)>3fFc&s(E2}ODlmP5>T1nE=2;~$yNmtr4kjH3=w5YcDsHqanzDjZ?CIAR`TJBi@Q z6Q!}vp3v5@k?qj|px;eDthhTqW%|g92K~CHed0{Q!Nt8Ll*DZA=_Uv?myHQ5Sb@}f zbEc`aBFI@c;ne{EY~?;H!Sr19vxh4%CHKE!5k$*+&?xQZ z^<2ZkuaHN9bBr*AB?bQe2-a#zh`eo@s?;b&WJSpm(AJE_i3+JR$&j+8;eK4A3?*;% z>Ddtf+$x^5aDl4zV{aCKUtG|f-6F1<$x_#QK;ZGdW|^ZqyDE7P#Z^HV;ZblqoU2jj&z6wvUAw4ffNnCRG{j$(>hB1}Q>G!AyDHdeyaV9ldOO^Q{dV6B@$z zMZRBp6d+O@VW@gr&L6s5Dy*C730e@pr_`Q5wqnh~c57jQ_Ct~729bdV#x6{qOMPb$ z0FC@W7D?} z6^k@A#cfRdYQCikJU%5|q($1e(bT?Z~kE`CgLwDwYQwzuRh( z)UM+9W-cUja!Hiud+X17c`LZi8EIHbPuE2SxtL3TO82&GybSo_C*krQ-`UH7EOC8& zAR-LQB7R@eylbN(FU`tb$fMwA{6YLYg@r070+Q$1#fA+=9rA04TFzwcpSuD1wfb4` z&6ynI$LAhIBtuXp?$DD7{>YPlblJO=B?Z#cbZ^(5bvxh=o8EFDLC#7XDaVHqBPU#? zX|0aFcxrtT%v<`%i{nuulCFd9phB*ZveFo4Z6G@>Q{nACe(LHw;p3Sb-arq6D4W4y zSf5^)6)a?nqYK`4caM6mL^y8?COQc3!%Pf2B|>Lar2aH{$Hg^g$cHN9ofM1pY^25*O_#Ji6K=> zAu@PUboM0hDyv%~DmuEO`rXScbAD0rX7U<|K9IWEpg#Yu!O@;Kf;sb{V6x@2sB z%U|~x>4$XQG~qQW1Yq%Vh17lx+c{Rod&)wjE#v)w)#u<-6TD79A!wSAoX|793nKSN zJE^#LB<^;FBA&v56BdKv2OHFhAzRTp(XTPY@rb|`)|%WEWoImpG1WA{jD(#OXQiNu zgE~9DkI0Q)Rr{8xo=)9_Zl|B#`>CSJQH}wZsWv$R286*Fd(GDaSVYQORLM9ClxozT z-U9#l!)b%OZ&&HvZ&IN`szTVkWUI^_@Q*q;O&5;=upd1q!FGKVsW|9+Ie01QnY;<( zQy!0K8x9HRn?k7#q>a)-a;OY96k?>9PNBJYp8E%O8 zGK(AwMpHz^1*F9AHFX8p1x@S|0X1vuc$GqYOS;`;C@wU+m-vkWcP#FLEKVvvv`(_< z#kgy*ie=Tu-Pa20j-m*Ff>&Z`M+0y3(EBQ&cY3yv808K;fS_hyC=E z8|Ju7m7YiJSMDzOYVos3o9f)E;u0YkGNLd%X>Cd(;E@=~(qFQp*!Rl0qw<5(3&Q#7 z11i|nKlo0v?Sou%z2scU0-&^jd@ zAjT;}f14f~wcrFL@|a|ESzcn}XL+?a$IGXA9>@Fe1^M8V1E0Q|z<~!QDs{bAKlQGT zAEc-*0wh=25SD#3U+NGqSuYcCQLhQ{HYm=cjz)q}w?}0i=({@?d{X-~AA{@3_Xb12 z;L`)WXQigoAg51mFsWmr&zKA57&1&$V}YYVF)HzspDflk748!4=-?6DcR?Ynw6}$V zYZ)>-QuhRm=E!MH9>_6X+Ny3;Uj7h?nB#cSIm?Vrz!k8qCNy3;Uj7h?n zB#cSIm?Vrz!kA?I&|O-%y<$2MVy}B<7qc_~mtafvUU@u(*x;LSgvB zK^EPnmf5c~+`oA^WWsEMDs{ng6-MzfrGP4R*AnigY^ED7aWEwg=Ku7?n8d-9IG7R# zQ{rGs988IWDRD3*4yMGxlsK3Y2UFr;N*qjygDG(^B@U*oMzae$;Jcj%=;a+=dSrMxr&Q4IzhDJF3;eHz;TU)TM* z{=M!e*Yk(!mk9^M|Ic+lns07SUyv$|dm&Uv!t`_^`_y+`O(=BS=gpz4i209oKX>At zO>c8qyY$l()(TiRKA7mLeTL`j^Vd7kI;`4W1gq|3Dxk{NgPv4t<7tAPu%P{N3pA!Y z(2Z8D!MPgo(@kD{vsY~toHi)Cqi}houahPdfuB?ODu}u2^(HN2>amYU7j21pX1e;6 zy0aqzs+oO+I0Mcg!JuvReM+|fY3T1s%`OLJ9?ta5L0wNtSsE(D8!n?^4pJZvZ&)gBZ(>SQbDqFGLQ2?Krs$s!D1G`GN(oKz?z9% zaAWe8o8~_H=0i9TS$IB)*0p|$|48%3Of8z`g!nYQ36xF1;saq;Qb$vr!ucoXJ7Gj} zrJpzVkovACJn#ZNF;3ujJh7_b9wi@JQNu^EZ}Sz-A_WNpl``LZ+z{R)%*#=uYOMHr z+naf5eQ(6d#om-RcaNsW*RT{DMZsS!_`vR^_AwmmgiCnn9J=q4WkbYgSos$ zs44plYLJ&p1-t?6;>3s|f_Q4os)c0&B@*dFd$M^Km^Qq%+h~bSGfwE&AJR1Kg~|7x zXkHF>2WxOuhIBkTmCjy(?gkb8GCU2N+^YV=@C1r-_l$>vv29K=ri`cWg1*(B1yWR0 zU%U(gyyd;|FjedekUytNW6+vOo9DmmyGyw#pHQD-$xhx`__XCaaPhzJKIfW~`+`Ej zB|n^Gxa_U(=cxGoyyl3A{{K)wnSTZq9|3E+cj%kO1uN%!T^GKTT}44s7sS zXZy+WMSP1Ffh}a%8}b3VA4uxV$;fO=I>=3@>UQ8wSBJCHJN_Ytnm?|Rxp_ZLMT#T! zKB&F^3%lu*n*g_VwNHhC5>ne<>b@3b?PXpu6X~t_)TQDi`s=3FQ>^}sh&o67^{e+_ zTI9@?!dYeM@Dy7u;kzQK4z#%-DoGDWJfgnhz>|R9NH6I9kZjVx*&R#+^I)bRND+NZ z-<8O${169dqgL?}9V{qd7%(Dzl-=q6Mg$Aq)rRtmb}BvDz>*3Jk(;#ttWtGJP02h= z_gUo2E4av{C>lp8ziu_z6OSNTK(1q#qMc-R;v*k>Q`MKP(!O6->1z9f`uQB3jlZx~ zftzAnN6sP-*l6UFUEHYOyD3foo;k$3jZA(=IFZcz5gUz}I8}CvZ9YD8>z)|!MNv1% zF|u>-toCr=PKy3s3M^hc6`9NgNlOvHvCnK2$5;@nxybaYap+DI$9au!WV%J15GcmC zw0Y4{L>deANjz_~z?HtdCqQPA3v*`UL{6 z-Qn)-%)S`!NpRHRFt6^a2-tqB1DnBhmak)d>GP(lDNoA5_P6J{`O`6V8Z*!r_*8r` zfT=7`TvF;2N<|m*l{`cgtI}e~8R+9fv`9y}o|Q?KgU2yK3S9XCPWskrjqYS;P#fFi z&?t0~E_MGX2D=$Kst37__aru>Glf=2Ehlc9%wLs94w^&YO!$%i!`^#;HI+X6+B>}g zNoYoDXi7H}r7EFUF(4{nnNaK~K^R384LuYg6cLmXs(`4WDu^1YfQms;sZPL#icY{X z2nc5fb!NWjdEWD`b=ErP{NlfGuf5h@_x|kbx?0f^gy_~l$PK2%adzbAtr!(LM3V_! z6hca`sRthu?>OgkoPeY}$43fbNFL&bA1*DFM5NeS^h+6pl1%BiMFFslfsHtap`l@6 zWSlNdT742}b}S4$MbJuN8xAZ8)|Vw9LJ506XQQt14P*&NbJ@6DviL(bW*d{}->oRw zAsH|uSsMjgA;bi*F>?e~v?*&2fSnOy6*HlSDTumb;?7GHls6Agl#b+u+8z<$e-oTG z?E)m)&~d!b=s{@lAastBut;}!6AE?i_bx)gC+Gl^#PVWef@#UYY>XE*DJondmw>U4 zip>_JD#5g-{Akl0dE5#4;m8oCGs(Ow<71{Mv0Brs3(y=XZ4vuNm2@uO(i!orhj z@M@Z+uQ2rr4{HxVV`;~t(6G>bkX7{fzZ|d&?3B!kqkk6-XE<;k4b#W{kFKGmz}k{7 zzR1Je`b*M}2(-SCfHB2~>2`iw;RT%JU@~NpfqVG7xCeE)Zb(ld3PZb>!Xbax4KEnu zJjj?E0=yObcmWUV*JX=jBIX6r$IGQ{y3iU;j(?&d!8BH(06$5AQYhjf9BeBE)#U`4 zM~1C|Wc@pEsN1s~IAo-6TMir+Wl#`66#lq>ZmBqdiekOOmvXRurHFVYD!m(TRDP65 zz{&D3`JT}3=fF3fSPV1eG#f);o(suB+LF$ix57(`ATAX##ax#aU*XPVIcYw?0!(-C zmL(PdPLMIMw)JDb`eZtu6no<&3f(kajaFrw-p5Wj+f>I(2C46{};yCEv& z(f-U(hQA^Oy#|7g7T{0Q;KlpTf^|dpQmMXw*9{p({vEJC22s)b(GtuHjZrD0x*-!) zTlZ7gN*4)RBS`Qq%fi-2psKL&sY~_|(uq*!-ww`z^61Gl$7q*f`!q&ch=Uw|Nz6)Db--?8-7v+8mTN(84!d5*e zk+8Mrhp;uYC_#JNF#iXadZg@F$i*@Gr7_Ug%DE)+wel)|`dYo3HGXyt8JF5A`H}2u zQP(h_P}DV~m9py2AM>dByK86>A?g~sHvQ}xlF=Pt)^KULYj|zBYsjcV;nXfAM5QPZ zJ%4l!)r$Y_8V>%uYe=n<1G|RoIv;Yw1Abk@_pV_`%{-mG&-Z87keRaFH4J@k4YZTt zjpq^lRG2V_pTwgxf<*mQfqy^|Gy%d#%{D7PPfS z4_8_V@Tzrq4Fdca0d7r^REQ#OQfc=s3D#jFHeyXjIM*$!Z~v*&@_>drM}@hb8zgxz-k3Z1+ zJ#9FGHNC*`m}`d>HQ8>wcRzsIJ1E)r-PihRVO{7uk*_rj3)Q>i@wcxvx*4NK=@t1} z{rja`Pc(vcNA?^=lYaB$fvgCcNZ9&r%G#G+w94#)NEwcvXV2u4c6KwmGdhAJ7|+? zA2CGnmC9IJ$?zFNbK@y|T3+oi4K_J8X3rUm8iXd(VPTG}(KF9d@7s=6xKa*DhD(%c|h(kWF1AY7Pz9dK@j7eGYQrWdCw58NmAb)g2Gmk5>dK-e7(^G zC~WOF{~>IJjcLv~z#|BEhiuU$;b+LSA+T=sB1jOsRQJ z=$GQk{Q>$~cYOD?#@+;dt%H$fz5+hzYxNt0i3~P;U9M0L|`cZe}HwvPhj0pGBrQBLdlhHU?O&9{fEhciA@VR3)If1 zAAZ&i)2EWgn+zP0>ks|e6E+Ig4GZt%x08#jz`Ei1q)uJc2v|34?|iFTjQ;JlY^5-y z0~^gEHpetAGD7|d915HVmW)&s@al68$a$S7GClm8VBnCz($^CO4&Q-+!_5AH{I;z| zA1QicFG4<=r8xzQ_k)2$r<;zk1lC&e)DS~b-%=Df%(qZ+JoO`RxOS5g>UM`Ha7ddh z2CitX2gGkUHg`WT?ZeyQ-BUi`ZB*@=KHdidhwi`0e^mMm1`Z#9fkR+G6gcD#DGxxR zubJ}m&1t;Y_h`ynCM&fv3_tY5zepSYtJ{v@a^MUfBw zF)nhp!XCp5wK*0NonYXQoD>}S8g#Zoui#&g&54|?)U+lN>j4-z1PHG`y-9xYK-nr5 zxoII_kUwr4|8Zf<$Th?`=)p8N6<&{bVh34&Q7qx4D`QVfawa|cAMC!Zn2hwS9N+Dc z95qLN@uH`$lX=cMP6Cl$mv-A59kB8w&|hhbTTFeA+x_rur|I@DhsLS|Zy~4Q&2Lmz zNyGaJ=6sp_2~E8R&cpG2GD%P3TVV^lIUV7^8sK!%m;5H*oIXR*aA(!#>=tGI-qIti&mEClk)3OU2#sr(%pWx$Mca>2BkW0_oT&2|ckNhgu z5!U&NU2FYPmc6|3T%$LQ{ac(CvtgXS#CaI1A%XoZ`_nnS1t5!9;KNTnuNH`#U8P>q6vC9}pPSw|`) z4zS;u9YT7C+SL2bcJ$st4n!%5x3xmhWNGq|mg+Ad{_C(b@={U9boSdlCUOO#aS}Fp zxc7;2x@8QPlVZI^IE7qRoU83~%}3fQ>#?d?G$+8HX44*#RrWeO+(ubGDg2{`Qp->! z!h=4Ay6kpcm_SsJx8W5AF~ij_sA|!eI#;R;Ln`+keYepH%{VYFj!xnsFQ_KT?UP*b zoAEZ~r3IqOP<&3sv;?`4`Iw9E6ZBqEZJkrO@AUam7qT$>ZV&P>ebmk&((voJcerAN zAXYA46Eci^&OH;oxxJ1G)2!D!*ruv~B6$VrIO{OSK`dg$9pI#}RYlp8q8Tk&tyk+L ze-JX;sdb{(&;46cxAXauBg}0B0~_iM*NS%x?Tydh2wxJS*4xGRv*jjvZxrM$d;YXn z(%;<90aQ~FsKz08Si-e6U6=HD)&Mbr-^NSC2^D zOEGXly;0WY6}D8L8!c3>|KrSwKjRdc7j>Yz%Bo=TkR16=i*YY{?_|*t%w*TgiHn6_ zU#cICzfrguD>PW_KLZ770mz3ZH(*=QC(Bmuf~jOIrB>K+4unwC5pzP#mo=I(GBeOk zZqM;$$7vRB-PUI$fTsQ;&9$oqF*A~cGcukm)F8TGL*Tg9%870iqCzDjXu4zdE-GxR zznw%WKMVEA?}Q#^B9<&{4jp))tmQN@P5~9KFQ{h@x}l`@d?9Gv8(*pR&OaG6uNIK* zD&w>Ql=Gt@Uyhfg77fL&hG%3N@L6k41*+RYY3+7mo|>PJ=Wm$u!^U`1NoQV^eih4L ztr|#2DFW83P8Or>UvaeZ12t@+bfYho9O>!j5PbM_tV<)A5K2L-onl|yij;!5XEMn- zuaz8gQY4bt)KyY`EQHV?=kh&>8BoKlSek7Iw8_5v!g)!m%m;z5_rX!sfl+qgx3_B6 zE902lm_64!2ud_{weIvJ#e1Hbij%+^I|HVi*Nnm+2Vx<$$8|l)6B>%%z{;_nUWIV7 zW?dG~dYTdEkTNd5D-$J?-JWNXQbgP~8>?#61W?5ggi!V?Tlw7Ra0!G=G^fwH@aX2e z^7u$5t%BxljV5_>%Je_0K~q|>&APmu@|rNIm96NDkxo@9PSy~rhS+I4L(OU?&^q`M z4tXH3W`b5gH{5;`m5)C%8vuKFq7@NMG=9_4 zro4s;Yn@QdgQ2WEfC~P&ZQn-0CF%^t=cpKusBHoX8mOd#X0ZHJXIfG zEF&uoJ^lc*%yQQ6mZ@QtMQf7Y;^8c7izzffuP%++#BMvUSfM_3g{*j-2Ozfzq8~+Y zc6uAy5X!$npyLrJ;QDI}9gK{o(F<4`i zuJrM^CW(%QHA@C}$i=FNO}of4@tRO-LS2CFYq< z-k5DizE=-H6hHh}Vw?Z|I9wwZvCmx09SMI)eaHaI2QXl2DLPupw0akCo@Nxd0TKF#NfIcY}H#^WJ!7XyM zbeq!)%ZUwL*WZ>mK-Oe(JvIk*ExTUt?)f5ey*3HyE?$~;>*hh%tLBXppzHNq;#_o| z5-#n=spuVI6xO+Y0Wk-nc&?!9^_C?ketexs^@={X&-&h+spHh-O~kGyvLrWWPT75`V_ zhgtbfnMdrH2HhLT3m<~4p$AIS^5kRv0Deh=w4ZralHM#35SwGIdD6QR=?puK-tcxZ zy}hkFCH&)@s|WIRjMP!R4yn5Xh0&4odBPHozzwNB@nzQ;&1&jci|pLV^WcfSevl~p zscF8}u@_jBB}di0Y!j5K)d1ECNy=8z^IJXil4__c#duMFg{QY2er8r;spiwy()6)! z-yI{^VfLM^+)K;WmVNgr&YP~x(oIu zV;DDJn}fNU87%`PuFZRJwDCpGW=m4s5str=1B)b|6$rQ@v$#?1=`LMbueFVc`%y}z zexIHlVUQaUi0!I-q9_(SU#D#z8G}rwEd;_Y=CK`ICe&W9|7+#RyW`Bkm70T%l~(vE zuR%qWO=ra+O}N&Zs%q6ntc07yQqy@>UTT6jMwWb5!Xe?%U##$p#dDi4b-2u-w=>j7 zUbCzw8u1V_^4hno{Rj&sto0}Fsm9CCS}StqDMvCZNN2ZcbDyNHNP?yvd8eN^nR;wc zmZQ1_;_#U5eW*F5kMs5h0Gk$68YpJ!c<%lhV}E0M=EP;GVd&^v1MwwOnE#QEv(joL z`;MIXzBLVr=iip7vVL6^iFy7#Lr) zh`A$qafh*$;NekeR?5z=pD94;_eY>Ah?#mHHDw8?6iYds-5RR6y5kmIp;pC3xIlhk)OCr16bQhQ+x zud|=r)Y+F{bS5lgYry^RbsE9f?1xcd30XxO3R_cND%Rs-rBpT(62^^J>tD>y-^@NU zJmOJ&Ms{zO0B>t?GidN=LYUA*164r8BBT}gE(R9~hDdbcsD7=~5$$0!?9fSxJAY_T zg(6>=YgD(U?-ejuD%B)(huA{L^nKv3ldU{BASRGhHHa}~9k!IFN@sL9)|q+-%O=v| zAh`~zx2NeA-n5nWH zt|SP|ffKu9fJ$`Vcj3d*pzzx6_qLG595GkPJy8!-99%{Y__8Kj`xZWY4D{Jr!q2cC_E3^pR8mh0YIIdX3{F| zb&}_Q=UAQ9LK|^-CbuXM9e03qY9U%xEay(7mu-x8dbH1%{`lMbW7cl^N>xZw!FZW( zj%&*4I<%);Pm;{nda@8Nd2ja4<|;y*8i}ev<1FvWUG0f83fsV4Sry!s0j*n1m%T4k z@O{EPGOOuJ_-Quh&>q9HzNZXrw|q*Ele!+i{!brFWEBn5$q}sVEsB!}1A-%5F?SY1 z)Lpy>2wB(fn_c&@H=dl3zfZE$dFuz=yAT5JWVMSuw1I?bF(X!-z+xx(iN4Soxz&fd zbUCe_=X^cnN(2eeYN5$40X=e!FUBDVa(i~1%<3dX+2;FU@T0aXyPc3LpdKl|QJAGV z)g3F!J-UMiqz#@}`o^?8P9ky{Si^lxHJ&yMWoIM)xjRO0+Q5CGBP4PcG*RM1j?t+K z)fE!?(faPz5`LC~+8REf6ePqM&!$7j>^ExN{|Y-wCTNcSzLG%hwA8;Vfm_-~hQ6l7 z(JxiRB8Ba2*3KSF%7p0w4<7#LWq%pzRz&NLFOWPw6KSfF_8aMJ+*wxJnhi{tq|-~J zz$FIjLP+p1-W>Oo(yHrL1ktj5+W080bxk?%h3i)$+!t1lX?)lk}qcO zbWZ7V4??Nq z*LIU@N~}`TkvfAU)OG-h^-6~)#0#V)yeX@nh4{bm9GAbbTLl(KOxPOu;b&b^?@M^x z0OO9bd!CPYSZ?!eMuoa14}S>!7N*?firE2J$Z(^Up!ZGpZE$Z&QD+q2wco{1;Zg0U zw%RD6yc2LP4A!ZAQT%VzPE?){5gf0AIoTbWo=G|Lu8IM@NYj?k3_(T|4XNP{+*9%P zYdX>aX_9CFXKb!O|G5uLG-Jc_@N_%t?>Mvx3FrZew+A?N)QAqn=gONxob;!@BeM?S_r%7?^a^ zUGG6#gEr<}?coUI$^if)4a6FaT1%+qwy%gSXw#;Ri_i51!Cn|(6J7;CgIT>t*(}Sm zpO`hiRvqHKkk=n;38YnMxY+shy{Hxyj1lGJhH`QmPJKsanJUvtD41$bP{qt~VJG$I zI3JpytRIuBbt>8YH>i<@eiH!RMol~f!wsjz{^vP54>lvSXiC-0%Mm~AwX>&)3t5u+ zWWao4n4f9a|a9cy}ns%z00Fmq0-b&ZUX~wiLWD|)I272=~2 zk+2tfm5xfJW42Jm`-~B9IgorChZ=~&*CqNbnfCcfuNEED5fR|t(E;3K$a+4`kR4or`PfR?_ zkJ!=yAPKkyK@y6G7f3~UQ&3BdHpdw_g#bwZIZP89^N=i_%RrF&Q%0wa&4@5vLwQpM zq>zHl<>03VQ$JMTDSY%*o`IGC$qxM8d3lrerf*mE+Tg5;S`;DRCfU%z2BTiS3Bj!Kq5a#N?A5V=Am`71J)ioo}zzGh?6Y0|cu^u|4?Yn^Fw z{P<)dwyaK3U4W-9z4j|Ph9k8?an6Xf6o3FgifLH{D%xHJ#qvnzvM9Z_fFvVh7J%CG zuE?L8k|f;KfjYo5uB0bduj(BEal-1htdq1QjDCBp^l)iAI1OsQJN5(-41&q zz~?dICaz1#b3HyRbH>ptbK{@j?FAT(uSiJ&{u=eSrvyYP0p-p^6WJ-kPNjyA5Non( zR}A9$-?KE03C_~ORk_o90BxmbZ+a`XE{a$bO+oMzj(kb!ic#!8@s#T9mOe zXA>JVU*XQBahuol6%=qBoNk2@*s6wKYs) zD7nx=F8B%uolJ)m($U!;e{9sbpNoG?)a=NACTen?^PCBo6-98!qO53*rdKZuoT&Gj z=X}qKW=n~!IUsM~Q(CeT;y8@|_ew3b6jAQWz#KAlH1{BZY0+Ij)1qgZODvgLk>o-! zEvgeCZ_uLzrbWX63!D%(N{4KtVShhh1}@cWii{Sy<+=tt78xjWSzS#*(vPv4c5zsU zT4ZCh!MG^JNRyVF1CG^%U=~44f{G0@zx0hOPGb^}euOOY;5y@y?n0e~Bfv2~$TSi{BZO;V(3r4Hs| z7&?4}a8-J^j7c|(XMp`qQxpY7>%AQP28v-L6kr_0y!0xxq`vjBU18d-Nz02ht=eLV zUeo>tf0PgmHbyPGHO~*iRS%l^(&0Wd+~&u+bs?FgUg8QOj>@AN+d^`CMXR-jy!Z&S zK$ID!9>|Wt;y9FCQ_*T|ducf{%83vU*A{q|l3NYj4NMj!FNa%S9i!HXR%>QmHn>`| zYo?!wDx(U|cjtnuHSMAzRm_-H*G?;qWY#B#lDbMRDWp^G2rnf(Dhl^#`g^smJs?`G zudU2&%;6DK1<}A5BN8XE}?t`(0~(7^T4?m&C-}Vj9wi>O+uz< zwWdd`41tI;qtv>;Go#E4rLy*7`czmy^`>+r(R?9rMR;FL7)MizF z9Z8mlrm=zN6frnZ_@gpPxfucQ{;7;I+D-5Mtc-Ga10z2wqq7IWT-R-|GJ5);nZ2BD zUApxYkEjqzI(oyn(iZ6SZC+ljZ$AowL{fosyf!^CaI|jr;dTY>r~^l9TT5`XZjl6P z+MA*K@&F92CfXTm_;uYoiz}khnt4UpQpw&I*T2LQKX{i1uGS7MN?WzNcIilDpX?De zMtKL0x2Z;Qp~2O6B4}3+TUQ?h!LKh|?*?~i5Td%dzx2fVG(?HaI_B6%k|||NLL|Xd}sml!ZUhd zrF<^_>!SsRZ-MHyx-q8k9rws)&st_TrCre1+r9Fd07B$@M_{ z5WCz&sZI*3A#{}?uH74DC2_EOW_xKnFns!ZW0d#g`(!=E!b}_zP1f(h$(j({wf<5033@dlGDNbOb}wd9Dy zglFGRBH{(uVgZKuY~p&)@El#N^`N{J5#HcUY>$&~IwW6eXlrkqpLl=IX(M3Wu8j9i zDC{$6tT5;MXuW1JRnaVi_)Nh4$SxP)%X~LqH++H*QG7{!nRIO8iK==16ds@7435_O zp1ri^yqp3@>m@pD;;+;lsjtK~6z;r?Ph!Sdc`C{2iW;Njc7E%GDKuuSDrr*+SmLGE zfQ`|ZT`+p`+n5ijUlLz|jnSZ8*YVCnSJx}KhrA*BIiBw`D(-V(5gUvM*dn$#mNuA@ zVQt4j87KzF3fNQ(RBF*Ap7#9m6}&xtUjY*@j(Jux_M{<|X!VfPECKGdwdlYRD@jy* zpmG}1&^XH+T&=y`>n$l+W#ngyOpN8T^c-g0umEd8c~^EXwQ*6+@kNPrtAPgZVRFry zi*5QN#D;AFdgsB>n%cX!O5FMbVyysCK*qugOIzr|iNiX#OMe5~p=Rrh+=1y7$pQ5x zDpV_TpdMVUfqvB!fyuO&Q?i<~T_9o&MEhvg<>x*NWv z-hcZ*jI%(!zx7Xoo3-|&B+4r4Q}T3cxg+xCnZL#kz5s`7g+BatcBQrzaeco~JG0hz z)A|=`cNa1$lYaY?*)zMh7yF(?yq?**NJd_r!f*0ewFHH0(A^)wR0;~G7OBV+mN}=t zep+u;XwOT%qG+heGzt2HAWt9jO6}dUd7gXb_49P==G%j1>kCOrxx?(yy)NjfC2yEb zq4?_YUa3}T_wiPO{}dP-ebS+Mj4^MOF?%;i6dQ%F!P1k5Vf^cReKSsp6BcL1EnhuQ zjz5i&(GSdFr{9*Gr-_xCQu;cRU|LzT?EZjG++w`O;FAZXjrNLeR{|@`y3`Np?miEn zj=$rUr(-es{A(rb130C6s%#(o!radakS9)~J{8hc(In%PmvdL_7^6E%E z>b{<#2b+^scZW&{Djx`}OLR$E`M03(vQt?|TKBu+P+`=mmexAtk0>GW&XIw_q?M)Yl^(W|wUuszBjnn!tE zIL6>bxZ&LwXx~x)%1^cpNjxt-y;m|c??`upZg08H$?=OUr6#qVzoYtCf{JzO(f8p~ zyDMYl{Ab)QKoq_N-IhIhKG{KWvY)J=zyxd{249OA%Bv5T00_x~m&sL!2TNOxwoQ^d zHsuvmKwi^F+U{@^nkO?7y;W_@Bx3KRpjl)aOdOo-vM#qh=lRE_l!VovYKqW_+a_8s zEcy~&KK*7m-lpuZ>)Y!qqV-zdNsA_E!>MJltM(3t8F^3ohQp#&xvk}B=<)OL?GW74 z)mw-IiwT(1`qyDBz0%aTF-H3L2oJ?i)5BlAsjq=h%|~jZra_H26t=b2XMF6`n*Xg#Yr5AVGjF8!QiSC zaZ_*l`-jrE%coqRXERoE!?`gMtmu_HjkY`quU$gNka;0H*)iRHj1dAhOi~Wf6t;vty1TYs#(GpAPP+h>oW=%cy zS>xW0plPy;KJ=WF6x3d8X1A>@skn@rWA8S5hq`0N-^LxtqMQnJ3Kc50H%DDJ!m?0o zOtOJkam+gHQlKiS1h@HPjCt*w)Z+^>+lP69GXkB zo>L=k4A;b)1JQ1P6H()SYxLm*j{v9O5^YU{+HoFimnEcJ58a{g>}$+Q#n0tvr|c8( zkgknp(avGCSa@R=+E$mm!?$6-L^p(msCWQq1Iq5pD|Vc-XvKbV4(;_RM&`iocN;_b zVwt2in8t3nnP*K*d2i_wOi>W0iKM}D3fhCuP?&Rk2dv#>AY@Tj*CkW{$u`~sE$D2Q zku!)lncSrGVEmDM7oVkbvbc1+FF@V{Wtmks)UVhG@!uPbwHE8GoA*B)ntQ^D8oPB> zH5o3ZOCB9hm4bB9?cHSscw!Jo>{TFKt@-?|Km%0-f^eP^X1)`hayVp>vE}F*UjP+2 zff+lSxGCr2y1$~^baT2pgtgMJ`Cav5vP{UeELhZq*-~a|a)MQN)LQB3Sj2u;23c9y z^19|ZWRa43`WZ*uRuEO6iep+`=i@!*9F;=7LlS;#;HZ?gH%)$YR9XB8*8|$19~s3~ zLVntZ1`WdE61n!wjZfow8%%scc`*=gVbT(lqx?d62bnh;jf1Q8_#Kb4+QkImpEw~? zj3c&66!-&QD)eeNOzee$<*Eh%`ULG5S$I!E8BXPYK*VasACvg2G_6UCg}RWx00bUN z#3A|^W$)FJBu=h?_)kh$K^;RjLlstz4H2PF!#RpvVXv687zWeUxXrt@t% zS*qC^+aczcFff~|A{Y63Ia%r^+oM_=7Vk&fBV09@D@lqeJ48;-*yR^)37K)ZXTTb8 z8qZ31jZ;Zt4EE=dW&i?3_D$9o319*G%{=C^2Y8ay*g)%t z0d}fK!QU(QMxreC*|>!>*Jw-IL`Hh^#IHPC8C*Is)*jiK+P|(}?9n*Jz<@^vm!9=k z)k!NjcVT&Nj>eRdSH@EkWhXDEh3XQ8vWg#&A0~VP@|yL?vvQiA0a41vMJ3+^QJR!~ zVS8>Ytk;coJA$36M1izo_fIEpRK)_;H=s)d2$Dh;qc$Etv>4vmSXes zlRc0tVan+eo6A7Z?tUeWfN@e*!-thnw>5)Ii5#IFvAHeAE6W&x+2~{$xR>pHasu^E zIm@b-(}=1cgI0DYp*};P3UZI!x^tHMl-S3lOvs@Ry`~#wNaMf zrl^KTpVEwL7`c6V*5X6HJ^_|w8&QS+qtiLtJeMB z36%aCuYZl#zsBodtEyb zuko7rYrOt7UjG`ee~s6_#_M0>^{?^z*LeMFy#6&_{~E7tEyb|Euv@Ia5Sl zTSomuUI#M&A+M+Z8}hpAzmV6lTatj1{~)jD*#A9wE&hYNrvINMucd(#|C{8s{Qo|A zE%v`6uN^lYzj;kTfpy5bHJjx_zUTh*>+^x5#}>Y-Sq<^DUYD>lX1kAXjJU2K!OD+{ zK9oE6k>?)wHS|stP49p_*4m-!Z58WsG%VBh%F?Rh^5-gBqY+MV5raq5SbN`ATGeO= zm8NkKcWO?i&Z-@rC$Md=kj_NVeQ&2G*bvrBT++LAOjrBWhLlmbw!_Qxw+9=Z#}zY6 zMjBlwnw~2*#$9yU!t_|H?wS0d*r@dFhuc)keFxm`2$H;f7U`|}E%Uzb>>8J9BgERR z`j|NiAsU@%2ZGv{?sD;^IcqM_3TwBHTyi3y%c+b`%DAH`S6it}@;1z%!qaDN4OLfr znG0Gijhc8yg+sw^n|6j@LK_!s9Ueyee*I^QlBJw)^xw*>! z4|&Z5$!k-Pyf*opyguuodP_uJQ+K*&JpE7dnyjqpR)qDq4!3gR`Z{a3LRRdy*tgFg zqekbUv)IXUnr)bacNOKA=CZ3JHF?UJ)3{{w1d?8-pX{9JIQC+NjdS?8{O#VcD9OJ{ z_T>3vq$=z-T&Zb0NFlF?qIDkH6M(SYks7uLP~CGT@PB-}lK40?PO_rgQO2FB%m)+^ z3voH*oVS}aXFKK9)6-l`JyX1@;V=b*YV-9X7EA#&Y3Pn;F=a*6 zi>FZwUghL_03y4)6Fy@AF+49B_Zux1^5^xm1N&$io|L;AhWRFkxUaO7S+)jF$M1T+ z@|U}o?$hYRq+VnL*-b#a^o61BlPPo{glgTG8Wm$KjbGi9`Q*i%M^c?x6tr~KMk_x( z!O|3#aWap&zQcAYx*@mH>%doM%!^pm`fIs%f{vL|}W3xrlyyPlWc&p{Y_zxC9130O9P&voGxs{gbXnZN}rtQ3G6 zk{Ux3`(MdxZ4r5GuuNVL==#PqKTcZ1`Tal1YnaSxW*TGS^_h1cC7r^!=6Tb$GEMvg z8_GG!o7uJ`e0PwpF%u=f02MzO2%rP!&@)pol+i3eXasN^8WVe#{6;z(0`XkBr&c$` zWg=A>5?jz;io^vd6{-2kEa{|>N5xEK2WqFbW;8CkX9{Lo1QBQ0DBae4i`5~<{dN*S zsk3{eS6j88#tI zXO2vq*uHqxD%Z4o5=G6AcQWN{c#h6YRSCvEzBU(f-AKU(_icy%1|0*Ko7Xw1+ab#Q}8agrd$BeVJR+BQl0m*^qsm zFZ+II#d-dcOpv?uY*#$(J-ufw<<+}Io7xN^U{%|&LGF_Jl9~pi^_>?Fi8T&L+q}a; z($wIUy6trWeQ*y}Q7a8r-Hy;OwX>>cPoCmTz;3gmZQI%K4YOuF&N=Z%Wg?PFCzz6Z zb5`7?)^fTOqGhsl92M*=?Jd;Dp#-JS!nJfP?fN+HE8rmQ1>&+i$YVt&LVGUi3@pW_ zKs(F2?2^vGJ=;t$_xByaUX4mSUki~R1P#BQM~EKw;#ORGyTPo7nDs>=-kBGj^KA-c zeO)EvH&Q3ct_acV;g0ZdSchFrh*nSWe-fDbyW|vizqIECs9>Z`ZEBU{S(ac|(6fYL z=~kd;D+FnOw6RN1z_QDck2{dx)$$XNaUV?t~RA4V!ZxU+Eb%$4$_GOkn_eRj*xm3Zt=pTw?<)uf!RIs z}(N)of>X=_TmRXm|VVZ=6kTEVPu*(! z7lhqT10ie%dcP2YVq&gm+pMBvDO7|P8Se$aPI1MaCD>#L@Qplt)mimR0@t{`j4fQy zZ3TCx!Ni5)hdB{X>97#Gnkk@4N|)O7Ji?<6A#MYeW^So+bX_IH9%ZAmX@~*3%Vv&5 zBv(tCXE!fI%W{#5gHBQcq#psgiiw;xM(m*@4+Ho;0x=iPp1VeCL=^VgWeS@a2U6Gv zzEjxTxE);^HPsMv}7%2sn=8mDy1){->U@W4^Lce(ZlC*vuV70e)MNR9U0q-(GOxISlWo z7yR5LvfLN2Z^|V$8px=&;W1jdp2$dd!&QVhrna=M( zGq|;5BLD}@;M1CEA~QH6Lu3Z0r_X#hgSW<_$`2l;z)~peye065XfCOUvaAN@gw|fG6WN*s$AFOIDT3VY#Jm8I$fl>&Buc0Outx+` z6+tYTDv`1zNC{yg20lx+EF;;SAd*e9Fk+lnSSGU5%<{i16WMFCrSL*%Y;-0Ucw9CG{!X|OivO-Keko$}QLjnh-eM=i-tg?@qN7Jw`1bAHl`Vdnd z*)DGH0brwvD1q=| zoa1EnnK^E(LF|Zunk5o-_{ak7GE4H=NMYHRE?5E=kmR8=lMsyrTq6&|{et-pWhc6b zpzL=f_@dyVZjpKMM8NH6C`bfL^2LpL;)zw_rv>;*O1=evMGAl#21JsATEPVrs1nfv zpp;qBIgB3x5F~38Wx8~?iKIJUXa3(%wi?J*LnJ8N?jD$l08+{q0}m$kD22d+5Um9qoXs{`d7b640Pl)c18$j2ZE zGg4GxG&zbAdB?t7^>Vn1#25$lq#34{oVQ3v8P8w&&SHBu=+;59^oNOY%Ph8$Eu?Zz z5@fMWL@aiph{a|e*rZeDONIGRBx?6YmCxwya5)fPiw~(=qe&^zodCud^&$kDTOSD` z*o3;Y;i`C7j)=Tw*0=M@BB>3Dp`^}_P`z;}zOU)23&gWJa0~~9p~AE&b&;X4MMhrX z@p9wsSVaNUfm!dvkX#gAjbKx3lS%4ti641NX$+*1v5{F56i$_^p#l-q#t06|m@7Wa zhp?#FD8r zqyBH;`pm(SAHX%gMFd<^D?s47#1&RB1kY-^@p{%(s$Z(aX4Qp%1J?x358#^D62ZCs z4{%LrH~bs8rtKbKqiE@K;Syg)ojO{4hUR3+Y#kMNhdBCU$h0DxGV$L(Mm$;u zuAf*ceFv_;e7SyzQC~WLpRluoM(LMc-$mT`K<85ZIuN)f_r`}J&7|OUBtDgpFRxHV-mHbP(=i|20Qc7!Uig(Wh$AEJyU1`0@sW> zN@V~2?ROoxZ6I(xn^I`1c;Q-rDcYu$IFA2Q%4qc=d9&jfAJA<%1`z?*ytePaweD0K z2wXoI!JFLFQWa21bwHU%-lLXnQI(ZLI8ED;@*&Xwj?#nQN|yx!xmw z-j`pg{e!vAd&b~Y;BsXvA1$zb^Nw7To@QjR>sE<@?l2e28#5tO5ji~Ep38_~ z0Gdip%K@HcwPR-~X~6>QmsO+h5-@j0O=K(YS!nHWCc$gB5p4x{IGglG9e#GbQL_`= zhYRbpLnS$*e>!9{8PQ-hQ`Ly zltCJKZ=?~hwlCwO6AA-j*Zkb?*tPzyH1*01LZ9GjKzccQ3~dL!*7g`bt@v{K#ls^L z$x!p0w|LC@IuN_wbL*u&^X1I4EBx)!wlv?vuW%o(%T}V}=G0z}*GYMhjtLE{BuySl zQnuDb|5>jYlLw$jAnOQ|Yk7@jN|T?$IeVT#VVqaEL+R|B!;Rz8S^7l%&^Hzz-&Dnt zc3S)}g)?tzuC#+ka36kgK+9BSk;&tc0chhZZ$VRd@+-_NHT~JQp{;uFNYiR(Lf#P# zB(3LPp`=lQB9g@+Wq^peHh0g+;n#|oYv3J6H?3|_&B3covR_Jr z{xI2kOmIql=k~RaALdCC#0#rI>BsY3G}tZyrWg>?dvVaE_YD)S=Us_v{Q-v0;bK-w zmK&k!Ohdc(y>d$c!cn}TEpspnHZ#Y-sxFN#@>i^S;L)ihvumXH#Hrg`&U~a}p)=hT za#Z1j1aSkKqLxg>C=c$K6Z4@yb6L8wiJYb&colE7=Ew&^tKC`By_)Kv`C1GDPzQ9G8`OL^n;W34V3b<{_ z){qx!_2QYCQNb@GL&sy3g)=PTHKSH@cJHE4diTT{Dh>L=cs;@YYk7usAni{2P>$(? z_u9VjnTla@4D@K|U+5^gY{i!)mTRkn<%@ERxohS-JD#1(mHCH zw2o>eEE$SW>w$XBV}iM4=xnE(2(<>*V1rzTVLV)7Z$|jWcQ^5$q-qST+w2=N9}}Pi zjSWIIZ@!@Q2VPwS;?)Z7r4=H)T6(Ry2(NZvOIb{+fp~RwwEDu=`KJ$Gy5{Ja%s%4c zyRGv~pIc(j8m&(9UM%?i;3PZY+-hZ$1Jk8f5okS?`QryX><)B8)IVRgqzc=6p$46| zEXUV$-y&~#d@5Wzw#`}^Hhw_3+Aa;3R8T=>`POLl$QGFI``WFh9cw=))Vf)fF41G6 zgWI#+?8%H3$XQR>7Cl)#vZY8f<&}wT>-Ouiq%${Mi8jfyusPxr)hgst&mHFKC?*h1 zI4i5JvF=ItJB1#n49peF5FcHs(~rL#nqK&texE$lr(`Ssv=FWt;YAxw_f|eDw@VhW z8e{!#{;!(EV0cl(1LtV#Z|fOKMjvY;BdXjl-v43%Qq}`MDeE&-I{wzhdIorPrkvlT z_9aM=REYS7xpe#7cgmW?U%gsFL|G4fr>u*wCW4f;4bQTtoA8kWQr6;HZ4Ns2S=)P{ zlD{P-tb)Cqsl1UVqO3{laU#l^l&T6+){sWoAm#y8y#i9En^A}^NLd5zF{@5}YUlK1 z5B3BZU9)@_WN)Q+ot_6zne|lL<_%ejlG&DhWVaN7N+|0$vG-qNcv^x**8qeIj+;(@ z7)-EukT)wuE1aOS@2=DS{jBL_QsaP-#eMQAWIkQZr*PmKahY%UCK(HI@{qW{^~> zQ7UTGe=bRso`4gU(xm@NlbD!(&;oUc$>rnr^=~eRN z_ef{m8@`fl8TQpWm7R^MfTXi;zer!;Wum8vlM{lF&~vqB*^i2;C%}qc(rYdJmXW;F z&TZw%gjLRo6{-25&(US44)H41E)N6AH1??Yuy+Cr`KJ@!Hkzrb7}VPNPbZududCG> zeHG@vZP&s|1+%%(ryHPi_u*X6`k$x3FgZsWm71KG>a#KwcO_*Ni40bc%&5+(TAN++ zz3&x)>fp4xudnh;T@T7-ywrafJ7E5LOhU++dtq?Ge?RYC#n z#3>uVQAuO=ixW-*Ap8|%v7<+yTAh0<1K}{iBo|CIdYhim&kRI?-L}B(01z_5)&upK zxp1yz8D+zmfmtb&l(M0eeHnPJxLPs&wkMVY8SUD~2w*)pm&2l=vQJ7-7 z7NoS#)@Ivf(?kb1B|LjfXAiE&z};~)Ln$1jp_GxnuA}3~=LT!T+XRD6`MFN-NDjyU za*f(rjF;WwQ`}kW1`R#B*51OslQ{bZv1cq#t$*TT?Vh)2T;&^|FkUiuBo}O1FSMNI z-(FKH&Dny|U(4Jha_Q996nxA;8VU?C1c2pJ9G?5CI!FJf9;~p@7j2=ydUsbRP-!B$ zt3I$c;9wW#%i6a;0uxk$F<}sbUye;acTGd8lZoPbn62u7L_*hU*K_+Q+F##+PEc;}weT=~SFGm+GSbVjuY>8kd!ivPaHSeu+;3) zvHp}7yW-pOMuZYmR38Un6y41fRNtruW1MfE8H4T8G~0R?#L@AsuV+%9=>Fj6tcDirgI>2U z+^-k~9ha&$Y(IJRM6x0`W7N4w>K}Q~E8trC5Xo{@o$aJV&o4`z3ml*y#?AF0@Hg0$ zRH9v@0dHfgSz|lNUt!2X;ueiiwJ%*mxHYSsz^E7V(h+suR}s6)0hEKXt!rII>%2 ztO5Ve2>=M_aDiW^2Ph1n98X_470Cei{(E2od7-}q&UnE=I6R%+jH!UQrexImTU zDOHtPRU2VdH#mp1C9 zje2RLUfQUaHtMB~dTFCx+NhT{>i>SndTFEnCm+7FQ7>)OOB?mlM!mFAFKyII8}-sg zy|hs;ZPZH}_0mSYv{5f@)Jq%n(nh_sQUCvDqgGtnsQ;f{uwHW1OOATUQ7<{_|F~ei zzjV}P+{M;+>%_{gHKe)Eks~E7@n~IkWT5-+(4#=+}#}Q zjHFA|N=ZRnqHpNt2`(R_=eo+d?ayZqUu~}EV za^K>WK0g>-+2j|gF1U2h7CVMbyARqDkVV&@3eAa~6$rEm4$)QAaJ~8#+k;v8$+wm# zU@P@1XF=>0D^P9()C!B2wV$!t>uc+K<~R=OZC-boxe2ysZ`?&#S+2e+ zJj{6-^XSRJGnWF;TVf!VMuGm;eCLkxzbbPM9Z9?E@dOBE-yQzCR37sCs2-{TTkbCOP#FV z%Bg8jrYQ_{I@kc&LBD8Brz=mDm06!D+cR9zhmkj;keP>3VHybwqhhQUTWnKb$JVhr zY=0aetx${|R^p_&epJm(6RT*#fVct@Kg0jxjnVm`&ERz<)n;~e56#8rZQf740m3>) zCn#|(wJ-);v1^CM_i-nq&y{M!p{Uz)L{?HGh%pfOXu}$Q`|8gOwWjj^CNF?`ffkUH z-5sJq6I|XYA>q2(QQcY*&ByXx4*2n@%M)z1YV2kzp^JS$&nxu^G;vpW$iY8BZQve8qYCe_7}Os6dyPh| zxX7@$Q>kI3yPYP#moTgJL!8jO?p<2?`)B^%9kd1KlBvqmT5c{xs7_X#$}~8g1cNr! zbgMd6IQ|lfuxkL0sSr$lUKQb_Cd8Y)i!lh`zqq~ez4Nwi7veSn)lo|r;J1egDdr)p z7_3ZL&Ie*kVr@J~xMEe!heoTUAkK<8ZX6;1lbC7}#)2ixf#r*&^x&%T9B?gX%WVsP zvc&)%M3G!drgiwd7d_Q!oj!-5xgx(#Z31Nx^DH z=R)utoqbf+<6u`@d`QicE2|Qrd3Qxh=TYKgz2)*hyF6tLY-YouQB77-jpOaywC;D6 zaz`Um-aYtN16vyU!%76~Te$HC&pP40XXh-YyWaZZnK$>Eo?h?E5!OP@cqQmQVU9E4 z2j~^B_nslb{3dJ~S*B1G75c#bEa7FQgV25(jqN(^ih27fO=pdS^YFP&L#P*6TcAFm z@7u0={xWnQ=*&6|+9>wB(G|~%t^!xV=%KgVWNqL~&i=8TV7Vq&c{9d~k0F1bI}fC& zYYYvC0DjB-2rvz~Ay6Q{Lc7nFN&6)l?tVbMz3f;`iZze3JO4%FPvEL$KNA-zbV)K) zEpqa{mNF+~&bEvf0s4)fJ)zxtZq{60+o$siSVx`i*NHzgiC^HLfG_B#bpiB7nXT1TQ%ion=i2 zdFof(4ZiK+bbe}=D^)1#)-XvxInLr)h5YSDY3gu3d@|%l&3E3F)1G3y{VM-5LsgXC z8u%k!s(pj7fQjUN$9TrDR48yC=m_SMu=;ybWU^ zK9sxyV8>}Kk9r<-KYAVXQCJqK_xvuVp+zWD9HNXlLiSK$mVY`5=%FozY$q!!7zT`B z5A)i+-brDh5l!fg@vdi2U1Y(-!xSghd{eKe*HpC#H+UI6d>tR1e2B(Z&8uET@g*Qt ztROe#7UEsycN3zY`8jJTOFgZ-_ZWd^Aox{lV#s-XyhEVmoRT2Lq?(dR>2=V~qquuI z|GY=N(qW(surZ(&XoBa+#80Fv$)X3j!Gwv|;H5a`5i+*!PXJ$)-UGQrw@1$C4F>O~ zk|U|GBw75K!vtaBL~!Cu2jw>`h|O#?w_*&s8_jpK3y9`g9hCqDgvO?IbhHYMh5pJ1 zW9J0ehW$bE^8%O?`C`>3;Hkv#N}Ii6E=RwY4|>gTeOMBiY&(QR=(TzIx$&+h`4V09 z`OM~svY_pE+T_v&Zp*4!-@E;sHPt2*VFz#Icm~pO)!Nh0Awnvl0Kk=(vKLglCGhwH zk*c?pYIC*#QUZMzON(|<>{^*@-FF-(p(4~Cj}GJHHls#Y zKyDIzW%cX~i498ERnR2=x;!q%0)k*7;zUR}0$UUgy2+GF;3a+EjMAZl$V~9O6jXIx zKk6{9<4jNj0Zw^?Pm)65LfFkvOiqjnk>cvmqhKDR^6!Lp;u#d}e3fgCJAF)7X#Xoz{x&D=9A`%Abx%fkB- zcEWi@mrkTXv*#BiD2m1{li(*PU-qP`>&!h`@G~m&h&_Kuqp~ z)=HtZjNC07(e*51c^(A@uJ#>>hmxurqv%sY)qQyS;6%^P+f?vh36Onk= zSXs~Zo{V9HX;P3YWqE7~{x}U#&s+V7t!edqFR;e{vh*GTsA7GS+bwFPCA=rD7 za?G<$tSnd?zKMybZvdQxI3)(`9NkCO#!gg$Zc0)3Mm2h-Z$hSURCGYYRLGFTYe0&a z=b_I)(DPJFGM{6z2jj$B%_S@zdH`2_;z7vU)074$4Y^`^m zDCC))NM!;hD+Y)WmQ0U0_~2fIe{d#tPecu$c}Pc@ZFwRQ#Re$bVLu`j6M1_iE*VQdEdOfq_b z1vB;1YLcSvSHY}!us8IW@-(9nixN_gxu5f@--pf}j=nHVzqDA$=3hD^D`X36`k#Sh zb#=|kjV%VCR*BbQDw}bsol=s-tIgV}(zUZpqnvV&R>f^7I_zKPB73qtz={ucNVHoe z!TU5jiNv5)RJ5!R-eKf%Zb1w(qeHJ3!B&jm85a>4y-R7VEG=SyvJ@FXbFtQ|Fs1^P zL=2RV=(~tWq(TPyI87$9ih5D)IcR{_5JbB6MBH%gA|glvUWl&yMd$4aCUVMG&arLD z%&f&`HX-JdGtf?gHWk5os1P$MwiOUWcldNjz*Yp@MhCe!RA~Gl!joEWMax?!$aT4i zzZ^_l?Qaw@YL^iT$^u|0id;JtVD1IUQ=y(D=!Q#(peWnNbz$^CT}7?xf=V_DLst3GR^x~#`MHT0@)3@}dxe1hxWFrZG% z>$HV`qS=C$S`2KMS|231J$dAkESlZsAa_mNC{L+b+X9|A3!s=av##j-$W{A~oL`J) z3(uGOXgv#BjAnmqxgm>Y-+idHl871oczKi|Qu))&R@|*&_7q_(y*+ygkv8TmYi5tt zxv&pmsRPGk&1_BeOTo$D#b!3MX0e&gzw_YXjc=DkOhb{&Kh12x^$MSQSu>kGP~#-Q z>o(y3b2EFrPJ3`=l&qP(4sAQgzu{PW=ZkUce{NblkL}Loe)mSmJxlArdO^!M>2(^XLVc3Qo10v_+4`D%3?CKHbgL zt2o1heQkDat%7y%!F4xrgJSp~;by}_NUPiWp>4?182w#gUCW#wi+dlO7{$v2utBu# zS-$^lJEXkXbzS$Pozw??@{gA}D>V^Z-_6;?{0U~qqQRz@{1=1S0#{iuo85vkr97CY zslN~FQ4}3%S^%KDSqhnc>*&7xM4Gp(nEi3mIhbC)+zv36ptQ$uDTVdFTr=);;}zZ- zezkvAJ|3a|$=2SqwvHlaP>Y+9pq!KJ9C=SS3VXGyVC$(FCne73crPG4mkO1bF@J}0 z8ko6}*czeqL!k!lXmRU3z8!eVgn&0PQLTcm;(Hj zhFXWUt(xiR?DK!F47J%p+|Ikj?OFXx@Y1@HqvY0 zgUk(~Bd?IqrIh}wznx7k<2wnB*QOMl`J83uRo8Q$D|)(k>^zMq*~YX4Zd}e}dm*wG zhQS)oZsy6~ef6#x=f%~48@O5bF)>>6oz8Gh<-iFGd#g!&PI0{~mpw5& z?9Lx%{mEs=dUA(Oyvly$I#i3#kl?cb{dc*|^3lY@1PiLmsvJv7(9R<@y<}7|P&fdx zp-8NOD~4+%$$ZZ zzbmpb{sf8E&)kW;{%KSe%pQM>njvNESp9S|@{I~eKdbHyp+`ZW_Ig19u`O0Rhi75H zxit#F`jYH|C1L^%9Xbpu5D(UKQ7sp7R|F8NgKez%H`E1r*N1jQ%?;q%T9xQQ@+aM~ zn94>oGN^~vcBBf|_6cS!ft8ZbDO#SbjESAcjG5Emm6Q0B?v{Rp_f+|AeJa>!=VPl{ z5KY*9DZh`N?RV}9{sQAez$g4sXQJK|a;?^~r!8H-A6*~l7H31jEL*-BZ({d6VNyWJ zK~uB+#K_5>Ao>gOL7(*mt_JWreZ$IW9C1cIyCkz(%SUX!3VUVs=ZW6Y^>YPt)VnV~ z6FB}x@8uCrxsw?q&E}r))d#-Zj~yDPDV9CLZzWY+^dqhwnJ{j+I2f{ewEgY}-3sK6 zaitn*bO)NvCAK6t&oiPG%;nd!mIDx|fn;s(f~AfIUVqjD{>%8qviss&k6qmfTr*P( zGH=z#dBVw)J-sDun=QXlOozv!zuDz@Md5nFs&HPnJUIleHEFV+A#dhL_e9O7s7>dkm*(HXekn!{OsA!9@K%{5GizB z@zYr`ShvK*u;%TNaLFvQjB+Zi#z*;ptryx?SDPe<+A!YeGw`?_mlo6FQ9!x@m zui(drXHNoP0yU>uh5KaQxfLLcPruI`d!p^cfv=z2*(V-xP5m~vY4AF1#63&Z{8)S= z-isIM{6n*npR0{NF3+Fv?|HK8j%Fr2pk`#3e;V$!xbBY`+w;|_FAabYb zQJ|;B6*Hgx3A5|zhr700e;gRTDER<74sCg_vs@ASxO6s{DIO)8K3O}E`gmE!i&PP0 zPB?2U?Oh2RFaJ@}99&SQaAm7kM{~yA*XN)?jmYOepa&i+m5!<9{fv7m*HZo~^kGdG z-Q~E_+?rv@`t}$26rYfDl%4Q}H*G!&`r>Dy)iwm1VC;3#k8`J2w544quL-i+?gH5= ziGCDSb0_|i&KhoubywsiGB(F)??~GXsK?PKf89kxjkma7yDaypN;)f=5A< z0r6*@&vVT?^`*XtTpYimGxchR2gFe>==TGA`7Y9cJ=C-?fskF}W#J2gt2bsS9M6_K zg7w5#OWn(>3(|?l&H8xl$8CT~u*MHV9p{r|vW|_yIu{W;P^{1l zBq@>(wbuTK4zoeiNDJj1Q>Q=dUZqwVlOpF*jQNzVW^#_Kf9R##b&{ zMAt;beO%{+Wb7NkAv1*Vv$`2-d*qdOSZ&c>m?P@+rxsLC$+FqZ=K}m=$%9L}qFJ3s zUf-W}!plxSybnJ}A9C}MWwS>D<24f{9JLZMXaN33aDu&|y@3iLH=6Em(=|JisjQN~ zJ;?XKCMw?pj!H#3+5r?YTfWw`-b;NyXy&frk@`@--x*zNiz*K>xAgX|X|%A$b@WH1 zmaKy=ND-^uQhRu66TW=rnxNDhhXy*gE*)T*?zaJ#+`pVAB9|8@i_<+z~BcW+> zZlSxks6=V*Atn>JGi7FDz;xEmj@HXNTkg*>ifa>|Sw(gKDy)Y=0vw9V6?D1n8@u#Y zy>GYL(tY&%vG~xyvWDNPqcN!g!nWxW!x_q8SR+D5{%*4i^eW!jCePaOG@qRG5q3^vi$ z)jT97C4Dqxbh9HS$`7F?I^T|7DEs+VKQ8rV*#@-Ke7@%d7^nw8pI_XBY(^eEry2s$ z$y>;-cH{4hrsl$CrR2ADv!RvkB;Ljz{9DKW+PsjnyJ>_KU6_Vty@`Mx10=S4i zWa*ml5ku9{E(EMvCogiUV?_uRvN_C6u1cJbm<~N+iW=pRq%ASMPqYoaMn@JQCzPz23`HjgQdLfjRsF=~ahLbzA~XT#JI*FSy(dvIFXv)eAH2fDtKp zPrNWgm-!@od=C^+8_sf*{q|PNeP@+in7sQ&2SJObuh*5Eq1hck)|>!Vx|uW8Hh$H3 zy^jN`PcR7}jT&eM0;IwMsA`RB~O>w&XG=oS;k|OLPzbhpPfS|+QC6MstmT`{41#Rnz`+wTmw$lvIVmmumSSo90 z7wwAdD6-(hj#(L{Ox*uhJ6m=pD*4?jdF1h~rpEh+CVw6@dTu8X0VeV8>#1V=p_!eK zr$DqfJ=dIQ_|#YudayY zx0TG9BOZK?Hyw8EDA{CwNQ?uS)$F>kUsdryRgku|)KlA0f;R27cwVx*9vVXJ zHB;eWW_o4m>~c>>-&xbx0#1xgPg`*>iOdxEZ;0&Vx=m8mAMXAk7bk``OX=Pl$!<2k z1Wa}E%_Fb8+|Q)XvWvAaIX927x5?7kXZGw&-p3O9u%lVG9r>vvHeTqwP~@3C&fT-N zo|6-|JUb84gAmppl9U)QJA|ccq%`BK0IgZ&PiH@wID|rkb@5ETlQdV;+1u6If}XUv zDXy7{hRy4Mv2?1+*fTTN)88}not(>LUs;{_8XxnSZ2`j{nGi1r{)<3rMIyxXO2FvFBmeVF9AOqW2JJ$<}jE z)kpD&i49S~G>~%9dqbF$0kACa^r--f!@w;IYYhewpCRQO%WoSz7}3?*et@Ob_`7^^ z;wDUq?&}tNa55{(Yu}TfU_*M+^@Ll7lrPGJ{}yQ2jIYF+a4!0`J9xam1 z)@*7ml_&-J7OhVy*2;k zVlrsj$}0kQOt2k#{*#sbiiRGWS78QYov&lQUe?u3_gY@4ZZhY-Y8d4UZ1J$yv!mr9 za7Mx>aZO_d8yr-`w~M6|);Ib$HJrw=(nx$GJ|UO?Z$U$@&9#FU&y; z?K~Yg*>w4psJh@6<Qr` zfJ{kh%r#FM2kiQp?0$3V>ygU}1K^<#=C}o0NZ6r{Q;K>j?pb|$CH5MVh<0zRA)%jB z{P~2M-YM`^FRg~^t_#QL{QF*DBIm)}?)LfsWzC{7bE^vu$@k?&CDe6R~-lcRq@@ zF^IbEK7fc#%P(J3CdzuN*@)pN=xiXQjaaQPyKuT>1MkGZpnt^)rHFh9-qqn&WM5ob ztaOzDqLhe+DQbwl%`Xrv;K=kLvwDR?Mgw-}{-bjDUK>ruz{l(jYDKvb5(ZbNRt4FC zo$Hu-1pIweB!mK3iM+0PvMu+Zqasx?ufwy!Ht-Mn1r>Ve{z1RA?SA>=4MgjSb@!+s z*lsCj8-*|b)2kf4r69*(#+m)XI{+mYxE#^sqTr(ff_U&b+j^-)zddI^FZ4;T@A~8l znlHfm$nR!7(edz!E=aLb5w;oC)8s>DJOr_a`FBsOkV}pSn=NOy?H5SZuwCw?jnQZO z14V>F%MvGmcT#~qc35~M?0a}Q)Oa>JML~?Pa`R*z*IACd5ZsHf*Gb>MF$|sK7P`z> z1bB8=954_orcdUbys7afa&M-VlN-9CKy8ABa*I#_6Q-(-OzHrrT3dqF&+G4>F#AK=nMEM9{<2@i&MeJEL=BD z=cXv!NL~FU2$gh^hPum_s6Hr9k&6YQ5`9qj=KiBbeIv--YGPFVk&2t~hfr|DTr~79 zw;lV`1r%e*OjJICMvscqgTY_bRvhRw;fn&!1pBL1O47i!(p4c6deX{Zlt(1!&ddmj zdsl_!S`v!F54oy#dBK&z{#iRH%qrvB4(0RyU6H+t<}VzBlUtu>5Csgh#U7@f&)IP8YQ$CG6^p`4ubl1`Bp&Vvm4+%U@OQBz?=D?-xJnr`Uj+9Z`ef~mx+~u%k ziXxb3+YeB&mfzve7`M#V$-5QdJB>OQ&IMGFy_hVf=_kL_WJe^c)w zilwlqR2|gOu9)1DloKB>GQbyTMsnn6cw%|K9%f&+PGD&Bp$<^9+%=h97D&wA1VI+< zGPD>^cXR$@m%WDnWtWBI+sw_X)ZmsY9!;?)#aa55%G%buAT|OJ=Eu1zprb_X7+nOf zSXTMOaO|CS9usCZ-j8Q9l9xTV&%kqCFsB=e(M7&be9}m$%J^$%ww6F00_}&y@YhOO ztX1|G_4mzJrxyM#vT-k_HB*rF^(zj_kTQ5^@AgYKaUc+0MF_9~j?Ki0&8x6f+`EN? z)=Fdk_}Nl($su18FON24&afg_WlK5AFI2Kwxe${dXBYSKBHCFBU#ZL$3bt@NH+SiQ z4bL1TwUQvlA&`N01Bh1_8|2@re&ybK{$b6!TogpH`C(w6t9cvqq0vAhT(uWKDFPhJ zA!j+g!ggg&X`2yk1ULIQ5;A6vPJ6c#9L0SQ$KyJlnr7AoJ9Xe5fX2Vo6I7NXq1d9_ z2t=z6%93()&3RG|Mt|GMbGl3?sbsP}O&2vQfE+cYV}fX*N})`F;jv7=9biiXvt~f{ z7vxp`l7VZ-u>aj47el@-o42KsiwkhaH*UXQE&weon>J^H2w*rx#SJ+Sa(5dSA=fu? zPbZ_^ImEw0qsG=vZ4CqP6$g)>2Ot}%u&-1YMS^%pPcqg=&C@Y+%;2^4=sO*UM>fMg z@{wzKP-`*pS^}>)jI$viY}gPIn`p-Z%~)7(6_fO-pdf?9vBp*Ld04dTjeex^(B>3G-@0WCsoN%~>0HdBlyeaTueRZ2B z#TZR#_9IqUGJtqCF-rnuFWm4~5@05H2)7#t|BaCe)%vf-y{hvOp?t@AF~W%sY!j+C z(YE~}faVE+199IV3(_RP%Q0XVn8ykQnG`CbUI=z4rXLh1Zt4Kw1k9Wy10lpq6j*^2 z#6pux0t2J56V!7C)yzXZCE*GgFqNLHp(!gnBE-Z(-If6=qreOK_{qNP&((N}7)b%WP9I&yY9W6Kmb4$w0r^;>8^v|`ezEbln1VWJR@%g0J{s(?Uk^=_vl(0lte|oxtC3m zoKO-67=`bz65=iTbIhBwEY}`J973S~cM_Qpb-Eq$LV_=5q>SEBP#5@rrT~3>99y+8 z^#$Htf-?9CmzUtLQ+K>1z^VucKOvIH%aY#Jx+b&8B;C$r*qeV_WExXuk)_KEr*;E@ z0(_C|-4e>p0t#=WpAAHTqJW(L#*r)6g60Kuy--lCp^LVd)Tsy3qB~gf3N;pZ(Dgzz z%dU88GrB=WlGzlPI4$Al{)zOn0{|$N5Is*tU!-jarX%A8Idi)+Zcv#g$n}e@>zKqCQkjEV)W2c!>2Lpn$%Wr5{^gQ+ zN&n%JNyTetR}Ik=VSJKGG(fE*Z+yU&x#S4@0+J9s&w!j(z^>eC|{6tHoBQrmVRF*0Mj1$$(?`zG`G4X%{Mhf{S zIsMl@I~h-2S#CKmIB#OUZJvR!S27_>GX5o$X&3$x%BN*QnPN$%WfsVUG9l_8p&V;} z>9+t!V-n-Of#!u!V;NGG8qXa94u^uy05A_K_HjcclMa$2T&*UAhgcR}G%8p}MVAy+ zS@8gkoft)mNuipOVW?-F0B<@$QKVIQ*ke(2=pf;$;=nm3-7b{@suS2ECa&K3Js62I{y$X6YhTrtUkPjK=UOg|>@S+4a&Ns?1Ns#T!Wi zsz@SpKl4>{@|WYCuMSfi7O66`;k1k@^XjHvEK+5SH@gaDRGD^Rkt)*~+G$lu%*M#BwSrphiiE6@Fr%GPHWrShkX2sEUDOFXHi zW@?oy!4->GNIme>x}{4&7cL+ttaA}mX{W(^3Eg8zkoAiEsCgn zj0eURWWvcss!UH*jRrv}SQlzT5CLZ;0e1*7%(GQW?pQM_q=$Oz4Mon4c_)bht@45J z`k|?Yt-l2I%X$>5T$YzKs3-}MG#>DVf`tNQN+ggQ1L{J#l?VtANWf+?eJy~rGTLps zaSnW$T*g`Pg}sBgHza5{Np5C8Xq0vbCB_}!Z|AON(va&sDI{vdsKnj0s&NJG2Dkj7 z%6FbcgOaGg8DX0#Rwk8Of&`tB+Ztq2+0{`dm0RV3y7m_Eo?-w+t7ET4Tl}>7=x}9G zDl@NWJ8HQHV|o^Zxcv`>GOFy+s!RJr6=eb7HtnO66QD&O-N62=tYmo{s){X><7cl3N)WK?-<-$Z2wo6Q=YSoD&L!3H7F3a*4~S9?D)@AS*r15MErP>DvN~)-47S3GEK%~^|8{e4jQjVt)x@=@)N})4WtL?D8>VB4BTD; zdL>>=r5j-ms9&3T)IliBxru98@VTX#^i27{?H8D*@FB2D`M;=gVbP;65a`rLo5n~G zes$SuUx){--e$O`_vS+nLVJfSDB)YKDF)w9ci<+I?kE$VuVt+LWK)=k3ZkE%*y|rm z#Tt>?2L+2+Y75_XN4o#;uT|T(BbDd$!otMM{9mkk{?zG@R^Iw+)mgzy9i#Gz{_gFo z;rdCYVcUtjLNWA+zH0fCPsF$>H2CtzKAFu8VV26M^1>ojemYNApE%U7NVHbz7sw@p zw{(-Q%s>*weln>XX<8U8tX8}TgNVVU%(JiPWi{%B_@B?_7{R5w*BgeJ(vN~e8?1^{ zFmI?21{Rq3Qo>Mj;lM`mP{&Uw-VT))gq~OpwDLZQJt%g6^Of!f8#xIEV={ZIP(*i^}uAfK7DHS zFaB$*4VjBhneH1aJj0=$+V&omDar2A9CGC2AktHxCSa)&bcF;(d^LLG{=h69E84H_ zM1)=oB(|rhHy=>1vT${GElGd0`?w`w6O#AI3xR$G=12?vk;*IQvo-DVh_57qZ@lvo z{JG!_H!NP@qcz_W-)0;heW7dLIElxXw8*6Lo>y<(`EMs>Qh9+68T~tZTlPEbnzHSe z@fpk%rvNQA6QXi7g48Y+joN~ft#wt_XXSOF=yjTONOA~-p7|m9bM}w)ccv5|GUNt+ zZU5EPT7J>*iJ_iFk1Z=6dvl4`ED7jx9u7_G%gS?h<0H&9qc{>C6$Mt9UzJLGbNLG1 zoxZ1(iN~Q{RSv(nmQ8ees?s7SL%Q|I@IfbeL~6Kp4%5Oa-(E(Q1N|BuDf#C}uQZt` z$5*)p%!UC8+JW-%Tz7WUyq@P+rJ~5(K=?GXZsmnGvq9puEjvw%WKx;>AmSp<`SZV| zGPJC!l`b7UXndz?hoZT>osFd*FqI|WtG_@68=mZKlu>1%NB4;2_3f7iS7lWB>$6Yz zq`I#fDU<#>*M^41f8TswwfYiCm>qu+gxv8NFOoyI3y{6iVom1KN(Y~wUxhVU^CSDwhbLJ69QD!WF9cs_qY0T-W=&^KiOze% zZ=Lvic>kD8D{DN)Z{^h(IT2U)NR3X`2d`f}ruT3zuO?&17v}w$hzICTT;h$BqInYh z>Lh->|MCSe)PU~y45Cw7HaSm)A8{-={&RY@Q<=Lk`--LonYk+RH9?&|yfOR1rVYOY zC&u68I=9^EJGZ(_MXPXtHx%KGoLmTmxRl{mj66^fDf*3w2w{`=Xy6weDcPnY_}nEMUp9X&;9-<8!~lw#mGr&o=8|MZLAVGSebQ) z^o#BGduGI+fDUl*elA(h)lxQD?a!h%83dM^I{qa-bP^GS%$y$icyaS`&C)1rK(|ff zL4VAAlh@eCo-Y?^is9eRmXibv8!=g(I=fNj?wO$9M*E4Il2=T0oupC$XRbG<)M)j? zvA?n-s(K)}QrmU0rFZuIYHE!8?X{N|nUFJl`ons#;%cM7&*It~Z`{gE{x^>J#hv4l z^Jh_FP2{F|u(4!gChyDpKlpZ}<1Xv2!^h1%d2S)sa++V{n&u8}czXMrwH zJO4W}KC=w>yF62r0!UZnCq3qg^;Vb-u{pLyZEa;f@?C9pry3K&I=URw@AGD9#o=ko zg4)iTy4PEFfz^};07DF7XU44@azSV+sj|X|1)b()8yuhtMy@MGs_Zu~EiE|d=a5@l zukE7S4lz6?pLO9ON6TyBk&CdRXpiT4nn1#imZyxaE8G?egKpk7_2ASx*;7zlztFqa zsb|iP1WpF1)7tL8n|GFduQ)X7@3lH3+0|x{^8Mxe**7)3>rF?j;TV&6!Ha4|q4moQ z+o^G`je_wdOZt{7_6j2{^nLBmEknXi45RM?)Z*b7GI%JgX4>^yhH#^)>APjLz$8EO zu0XZB6C)S6TFrXf|3WR1!??a))$vngU0EDZTI*ZEfaa^fx0esa-4fvNG{0* zl>#Ms+Z47Jy!p0}m9}EKt{j=ZWmI%_KA7 z%pg(`qVkVcp4@%?8gJjvx%EdE8bqVoFrseh9Q~Z8FK7%&Q%qI1$l5yXLn)hK zhji?_Sa6B1I~rS)kyu@(8`0%;%{Fg^k7BvLY5?$K``1K8`Y9NaDl%r*dmrufJl(R# zyP`_Zn#kO&QMHS;rlU6NMc&(tR*Cl3)A%!gg}TV;9tM=YzR`W^@)|Wm>x3@2RTdbJ zf@~_P@Ik6w6W#gK2n zcBDPd&qUA(b2oHMJX|WRQPNTYYcJRhnl2>taOgs9Cuyha!+O;Ezze23#~Yrh?tbufCKu_hp^7h zR57zN)110k){0Xc*j^t7Nn6@FUiStxPsu+1ijQ-Zuo|;5Os5-Sy#K7HR!m@Y+Ky{{ zovQZciEo}d^WUJRKpXfQqryol&iQ=JfH1#6sy}gadZc*Gs-PHQGAK}*vB2bOk4f*r zi)YvvsNVh1gcPR`CIFr0M^7>ixoT0MPlBo7tML%*n7QNfYXJBK(le>7TTUBF6@P|t z$f<|r{;tYtHsm7CmdpX+2huUH$Bc8I^fKg*Duco%QhiV>b^i z3RAS~hWNRbZBR`X&5dUK8@^NGtVDjm>A;4j_0AOPs3nbqH`23@`6}Jlt&dF&rR|n3 z?<fLS5?e!YT&-F>s$zb%qw%R&;K$NOEadvyxNI7Kh9A2}U zUuT!!_cZK1R`+N?FK0riJxa$cXkw2sIO=mwnSIG?en=Umjz{q}dYOnh^N}{W0HIfQ z0LeQeEoy$ezH8)u-{wQfy^4Z1OxJ@A+p|p%Ox%RePb4F@`4>KH9U7GPy2rRlCzv^I zR(BA3xKB~PCa!NYKWn>t>pr18l@sp#bf=qc93NL3k%VyA2?J{v)qn+r*@rDye3eHCT?LrC%axa2C5YAPjNY2tEDj0sVyr1=^C zc{FHeaf>NwMvWY>lcjA{Uin+XB2#*#?S&l317Gf)L|(QQ1tdc6oyuINiw2x;f)@xN zIE93zHYFUGkH6bgR!!(%e$;2k=`fzm>n)VC<#%Fd^I)`xKUD^)8uQ$1pH;!WEBlyo z1yVO+OIz~Bd@C4gotI;H1TXODDB`1bzS9GK6QXe#T+@|-_znVVs6C%WO{GC}A10X6 zKxPzU{zzj5l8L^NnY5O*{AqcWi?*B~OE;c^?PG}ksFd!%bLPBWL42TM-OaMpGQK>^w!IcmsB1*sl zDkU@pMGS%{)&vky5rd*4iiV=1%N4%aA{r7lH{71az{?Ep1Xi6EHQii6Kp(*8m#cOCv8Jbdtrj(&6WoSwnno|D9 zRc#40r3_6eLsQDolrl7>3{5FRQ_8hn&KA&=GBl+OO({cD%FvYZ<1#B~N*S6`hNhIE zDP?F%8Jbdtrj-9rPANl;`agiR-v4`Gt@8f_ti1!$u3pgB7j9$8jtIkOU4f6k4fiIe zOn)orR1FPPLqpZjP&G7E4GmR8L)Fkw zH8fNW4OK%!)&FIv8vj2!R9zZTj6-7JN%pUa_kna!j@gkGAz~)7%Bx zx_8mkUF)JUt9Wimqa~kwA|p3+Tu!yFqGx`T?Y*R#B=7`-WY^LICxbX~^AM`>Gr^LB z^g3YRO1f(Rd#Jo|)Ppe9m;S`Gn!KAJl0Hc=F1?>03hI+?)FeMnZLFaciKSYquzQHAg-H!IQ>sT+2n&2^*& zF!QYnaHJsVQOj+A&;B5_2&FaVX5?Cq;$@^Jws9p&VV;^TW_~z$xA=E2%kjN=;?WJl zJA-k3I`rP=S~v1U2;h}shFw*8zMM8vRoA?u&(hI;c6rqn^90}Lk>;UbZ_SK$^ML7a z`LWk4>NTCmO@EV>Pn6Arr#*E=R!J7r&Z{uDN~0qOD;u6&+TmUK>$|qj0B74@OKW8j zei3v$v;Xbo`6v8JBiDjCAv)Tt5-ZNXUhLF%N{Lnx2x>Z#a_fEaUy?Q7-F~{TIdH3< zgNk$Fi|5{VJTIlhXy!SviE$L+a?GOx}{Q>iqqoPzP^&&PRC z7JNNUJfLTeVpiBau6w6qw4&}@&$PfDE~d|u?)yfR{674o=*ocR79-$%pm6HrN1d*9&v}=b zj>dMVc>RdRq2H6om!h83T{ST8kBRrf%^;Ntkxvco!xV?iQoZQvoH*u!LPV+0J5%SN z(TdVa5pgUIsBd-MVo_4i!o&`<-vKrp}TDAql}35};SGJm8ocH*xbDezUg*}o*|8ck%YJ?n5@ z3>*mi&H>%(?`vuC-Z9qau<hll2VkD$1m_*-iqPjs&O|F{ z#LhNcm*J+Cj6?3*0>#XEX^w`f7p((M`rcXLqusIUbsldMJzLXB&b#u~+T7qHrhqQ< zV{=*;H$RKi-w0~ri~V2^D@`dJdFO_R?dsDUPy@J0(61tUEszPVpM7=Juah6MDDKc~ z9PDc2sBWfAX?~HXwFJD%-aGyv$hVy{%PM(adBo7eor*NhP1gPd-%CRwn`^stTq<0? zOJypqfWTS`r$4OPZ|*;o z2uB((WILtazDA6U*UrKmmkT@uQt?|k(<+LGN}GnO9#e9|t48zSb%Hh5?1Jca{bU$J zaXORJ?l&&GZ+zubHG#v%et5qMmP;j3!cmLSDSOy4vcuooP}+?0kU&Y2;iiXD_%xTl zOCGYDUvcUVvw&1qCButu$TUyj2FgN2GKjQSiw&Ue{B*KOuCjf~nX2a#aop+`;MfU}F9fW)m*_jC)LV{X3Z zv!PCh%_?q$ zU-NQ1@%~pfQ;I+{KpId^w0lsYdhKqu9$Ji^h`3n$SyX?-TTXUb5>#fPgEMtS-!)-6 zHA;&>T%hqI&$7dWFRRWU;q~m@T;oo;+;RtH!pK>unABB?$#OAKyeUMt671v&nezdD zvf;eghhewk1CV#4a%sIMeg!S;B0+hC7GWpdOB*bIy9+SIFOu@z?3r*BFsPCuYV&!e zL`80D#)qV`j~_n8LvM&uA9MYvS8>ij$8Ll9Mg`E(;tS`!PDWK%6{VffCR(TWV9^bZg()4NgMkakL6P2#Q z1q2{W1xIe?4T=J4g+h-2R=*_!G242v;s^$GM4olW#w(x_DVc7YIvW!0$B#SW9q2w7xTPBxx^ZyPsnGKJ(MDVSYFDX)#*~8Q;TFezDnle z<3)%PeE?R_} zq6qnp!YKf;Ux_z32;a^?HKq`k&oVHfQZiLNU7E;FP>_F7>~`z`NUhi`X(GQ5UeO1i zVr0*7y~Y#a%X>o0F~}h<0BQ?EM7UVazE}}1gqg!jB^{;UJbCE_n_`2w7+ngipav$W z(k|yZJ!QdXfUTTY2^T=B6_69cK_CDag@%8Ig$X$7331xKH7+>BA|wrVMM$P`kaZlF zaOHu2h-FR+4~s~Qfz9LY`RawA7UdqSNmgsMQBA}UJ`z8Okx~w>TY{cpV4}t35C)DS zC%Y(EE?nY_6nE{bY9tkqjgSx^v7hS^xf)q2-WN-Q&BPJz|4s~I;^P&_Ty8E^nbx|cNJ<6h{^9HFFKJ-r4TfwxRPLa=P>X?s*(xj?iS%FU}5|rG+XeM2s%>8i^CA>g=9o)w#Pq!YV`P9apta7LgDK~Aobn^=LkW+d9M zMUBkV)~1r4C>$E%^!Z1Z*Nd_HxUe!Vws2Upgb&x^!Y<94i{cez5X7z%C(qEZ)lAZi z6i(wDKG06|j9ld@q+$T|TzILr4C|#J*5lw-3i6V;r81i6JTLdb=7WiGQ3ed`LKv2> zAn)cND>ff4WcmbFsdeih*D4+8Qk+f$d|O<3R6F8DABMjfO9GEK^KwzG5hfa7qH?Mjy@Bvw-aB!w6EJf?RzR!%)Y zR&guhJrFp#Z8H%+N(*s7u&aXzkAEGW~MKO-_}t@mNYwgZtc*6#@2Qxbu#sOB7_k7B`t3wuFhV zqG8)Dy{c#BFdHuN!ZFnRL2}$F48intHZRwZ8my(nZsNE*m{u%c0+mz(QjF<4h1tPG zJQWiSKx`HBlccK)8c@%$-Fm;yc<-|(F)iV3F*$`?-a9qC}MH-K6|Nqox! z+Gxn;W2hb`!iK4G1(3wI`?V|J_7q}>GijKKOnr*+W}dU>6a+}}-7k~Rgj1IVS#BCy zniC1j1yDE!sf`JMn_;RF_WoY@3eIuj_A zT&g3W2AJoDtTzERjZ9Ah}TCcWyvJE524(ceC)=={4>6Sg>_(BHCFE$xiKL##!#$T0f(_(JpZ#UnV;FoiEvS zr*LcYYQpWTr*Q2CyLbwo#etg~yYUu*^j&b_fXXfB_RIEMc*AAlQ#tx6<#OX4#1)Sf&(>j& z5X^p!>eOI$%X@F{A0p3%-=}!T*l) zTRv|oV6DIzjS#brp8L+ux!y%qduj2(=|TDECcU?gPS$k|43c>raZ-U}r7v|6-4BuW z8dafIFmnznSkJ{LS_hK(ljwTUvTz3Qdp0gW#j$F#y`wMap%!xS8tQt{RbkJv?~=z3l>!eD z${F-YqU8%D2R@GB_A!Ls2E8tv`(Nn72rjmshA(A2Is1cUb%xwQX*&O2jU^Un*j8Q0 zf2i*5?iGCmQ?d?R1YA6`kMD!YogIJ+m<9b}VjTl$2oRnV?mPIS?;JblguDjufVY@* zQ{xR@84u)D_V2fIvY#O56`$+pAjSp;JjDaNKKMQ^BFS6$Z2$8EciGSC$TUU)k+#X*j~#7)w2 zepz;ZV(YLr%q+KIn9`#r(S0$ihFObDPw8(>MiMKVZ0N8aPV3GpV(VL!g924b!)F-3>M?t#GSdh*G**THYeyI54y z_t@oz8uu@C{iyGve6t2h-%T{bwjpz+kxh-E`N)fK#X z00L>QSl&Ck$XK6jHsyu>zTlC@E&0`MwkJhsV{JzlEqOCTIe4(Ax1@FTqK^#gfsy!+ zOY?kUi9JzOM4zkP0*cUqHt{4*)y9P?7*sEDHula?F=sB{pMY^#VTifjURX&KaK=RL=6vIjXZ_Z`{Y#G~coUA16%;4gX~4L|c5vG?jx4nVI95*{mgV$=)c zUp#E{I@j|L%E@w=^;w5_B^H_a;K8>Z+_wA(B{HD+{*)YUQsQn=`*P<7#S~b^*iY46 zK#lxkQ|w1r9`I(V_32JJatH9Cl!>AMuj+OyO69PW?fH>t*oFP%L$j>Ww{xGkL388F!Nfph4*GyR{+ZB zr}2Fw_l(>G=oQn^eeyx}o{!V3o?bu=dgkibW~4TeeMDPXUkob6`9}ENs^YPro_oJu zH`s>`t{wa}XdiEiHZpRn@djAP$|9li8}qJ*Vxx6-0X?;B!pwoUgkSH!zTvp`%eH}2 zir28+$V=nK^VE^urBmUce28v+Z+ZWoZjGErdt``d>C^&c??PaA`InNG@S-xc`n5jo zEjc${R3pQhun)f=w{>flj_4MAOTJIKRQ^5kPHiXGeYfVc>wscK+aq$8Uqm${8a+GQ z>ZfKVe-K%-n6fxr<$~->^^y6l*%#=pVfO3Y5o;CkcVla>r=B);6<%`a+lIOO0 zu=OI+YuCNsZ{U#&*09fC>_@@{HIw(olbPSqvB*q7{?7Q_bW60E(m%o7+m^1ztmDyB%J$Gr@Rxs76cAi~Sm-*=efrlRZT>?@6>~@S%jtoy(6^CV*>tdtICC9Ej~tHti`1K+Y;L%RKhVsOiQ2oquE*fF~Egt&B_z66Cb>Hx_YS{7qx! z3AnM2mqRDZzP&U{-gCKZC0=Pe)3YBAoC9F*9$iMP#_p=ti9i?^%pR!m5O0ZR=A)*R z^p_3vOpOol75>BI>NJkCe^eVdT{J0^epDC6R$O%@Cbj zjaGvN9t3GcqlVr^xuhHsbDmnH5T&#&I@1MP3N(N!;G_jfbSH_i4n5A1kYo<$pu$0dV#D;l`l3k>;Mh;`Q^qL~EE{>n#U`mYERKB#dGn#bl*RAcx z>;y?8_Lf;=x73;dETN0NV@8_!>bWX*cV~0ct%Qkh+bth1RmcFVRL>PmIXPi68gYN8 z48^C~k6&puTF3<8JCrub6OSy&+N~^W8gI=N82Ure>099d>^FgFo#PI`c^3tkjMAV~ z6uns*Z1V7AHO=tJ!*>XmL(6SCH5!D~e7g2)GE&HLp1=a!x+>lZQR^{-8ncOdnn9Wr zK(A5oAM6mX54Cfrp75B^%jIFhs?615?F0rD=bmQ+=L!iN-qI=Ain}GhN@IDvq=6fK zy1rZ$L^IDyJuRz+)P8>9tnE!&g$Zg!1WjWP9nQ>djJ6s@>LmlGLtkcPlN`^^PZGD5 zOxt2^ze}|qV7Hfq+@csvvh_b!vP<6X8g=@*fx1(E({S2_;`RqG_~3ic4f$REv1L`F zj36+1&uK3O4v}1NkNmb%4mVMgVK%kDp8QQmeOpzSk%Q9P$VGv-?zMYZvhf@;g4t`M zEg($xc910H-Y))A)=5Qz#Kk?W#l18-C<$7*wL|DJ!PL96@e3(gj%-nKeM9ITi@!@i zJ^JOH&wV@#_fGMP4GDRdGx+ON7{bDs=*%rVsUJU{cg;n-XK=9(z914?7{ltCa`c`U zyXxJsog0R6@KR(Y!ub(A6HCoWmKw5lNf4KRZ!7_aiRu(teWn>K_;;&3$Ec6YIY@1hxhbya5qD&f-U*%!(Zd>-zS=Jn{v7 zlX;)`#4!-JLfv@1i%*uxN~PDH_RJ{s-W&5Xl)t~8tW-IHx_}CnZI+EAkR@xY@9Pbb zF=H!Z!#OamW8)SmH*-KE^vL00hI9W_I|uzZDmh0f$T-ycbo-{xD{b3&hD|@pC&n(L zG`apBN!urKV|}*V`v$k*re8?AYQgwJivk#bL*k(53q@Zj`a;ncioQ_vg`zJMeWBl=0ya8~y2}xf_`a;t8|G4zM?)8oQza@P|vpzC5rQd7uYKGud z;3ydw5%BAu@|AHhS4}=pbSoCOMBZvMttPyvR-D zu{T1OuiD)5D}D(zTSuG)9}Q-H9>WR(EmrQXRAj^J0LKUgEu9gL^V&Li?du>n>#_f! zeNz!J#&A!8Pp16Bgs6Ms1`PErENUw0(5$L$2xrqY$8*`T&V3tQ|AY6cYmdFumF8K$ zTNGlE4?q7!BWUmIvxw`H0Lh1TSWmEkXh~=3pBN01R(tN4Nric_S{M9sl&-#i>-ftU zD#no+qtU1ROovpCTJyTeh|jlxZ=A|cnlvM>7Fv>;IRQLFjkrfb_5%Ag*Vq%L#4Fq^ z^4Z&Y+p1%0EqP(Mbu?!U2@ihv;_H_r2}$dag7QP&y8e5lknG5-!%Jc2-JFGmJY-Jp zQse@gH3uAPSoPq_EHw{U_Kjpfvt|sln8e6A?S7EhCq-NJ78aC$s|;D&Nw(^XQ^|;d zpZlSG1LIMi^<%b{dAjuTb4|niCG$_28Gf^SFOJ z*v*f14eQC>0AWTB;M4)ZqGx|zIG%~=L1NX*VIvB*gT7=KK`Tdd=LlL{&prf!NhBP& zoxGt_ba>s(-$}0R#M`jP*(F(yCT<5k!A^hVkS?YDQk{a1dM(IQ6pBnj~JHZr{9jp7|TN-g-yYi{Im6 zhE(ibSri4^#n@xTumxG4Dztk<{<<_d!8t>RqCG+)>-jjD%dRI7beCNIW+fD zWi)rr-d!VXxr#PSHx9PEA+P0n;Z70@5edn zYsFurlDq`@#X{OI-$f<@A9>K-jutJ&Mu1T-1JtgxwjG(Rfjelr@~Gft60X_Ht+$*P z7^K*9u|cZ)n!(4diyk~&1nRX?;A&#lAYsK0*YNs)d9RrBTkQ=(ochSHPA)O@7lfl6 zmb(iWezW|npil4JAI6U(Wr8Zu`kd$d`IEzsd{TCx;PVA`0quze}xd>oQ88|4q3wSq!6cck42Ja;W$djRs~4@;XK8;W_mxLaK%SL%llvQ@u(~ z{zJWvig1$v+*69bQ8|a}@pT*|jfo8rWiZ6)nhaFDH+~xAe|@~=Z}sYX;Xl0V+iJH* zFUiHC_~$3pVKo1D44_X;^bA?+sle$?qE)54mwW#yT{(Oz7q)YDHSKTd`gOzB!xF-b z5;6J;SI1fFvH=K{kdKV6^^FYARb=lR5m1!qiLbalMdSw*%qfaWB8RUoirTqYRg=5- z-a&}Ks2s<|(IHL(` z;KGXK7UrM}Nlxx!VCPR_jsmc*7|+e39Vcqk{298sz)tae{ArK%D@4c&7K{jD!8TOe zSFcN{{ElpR15LMB3F~YGet>xER(MgIA2%-h4f|ix^>NX^q^p`|T5~*16Fkr{tA&{X zutF*7%qudVgC9|ltpNC`F`s7~brh&xmjX}@TgJR1=W>zHIU<@AJ`;y1R8!%G>dh}I z$aTaVeF)1`s)97^j1uE1%8RN(%}LjQDmAlzm#)$yp6!TbeVE5FSdvoI9MAtLU6mWb z2QY#X@z?t9g?+#v-?1yOQ&V~DZ|u6N<^LYLQes#CiCy1! z-R#IDl9)qi7GexY=BgsQGi_%4l~!>$(p#I9Yp*slMMU11X6BVRWDt>y`gGYaQSNTz) zsVL?BiNC#TLE2C6D!%wn?>bAv>d%4KKfNpYPw(1Uiy>5sv*Y=O3@0G z_f>y+*UE1vhiB)&EA5QUU*44~!OVGA#mO*Elh=3goOjiq^R98HR3)Y5EpYca?+TR7 zc~?4i$&IPwKfNon_?xex#h>2QV@v&~O!0*Dt&gSCNe|lH$nIErD&Ux4VTWj2y2P1;vtT+sd zf;5#;wco4fo_3%&!^1eoz((TBEiEC(oAke{oR7nKFaacmlrFk*TaVP?hujc{9CbQ> z>UKGrGu(*2s-Yw|@umG1{nJZ09_Z@ErUxh}<@{-)<` zApe(lO|`f@=UuCA*Nq;(=DeX{&b!WjlYV(~>hNz!f}cv?d0#D+eLu0Q`&qU8s4EVw z!py=s?CRaZzWOJ2Rrw3MN+qN_h^rwhwANwYFDA(CJ_(iZ!mZbqpxK#8Tr)gY>g2nEWy3RNmSa$F9denUQ=Z?nyx zsx`ZbzywRlnQ(?*$?+OYRXhG5qusCy_1m{>gdAR~WIY$}&%ES@Dw0i0IHl*Ra$I8D z%x@l0yQQm37*<~B2g#-2t->}0=#Q$LW`!$}C`X)O2wv&}SlELxUWVt@@aBMzMtuCn zNVjoZvne}&hM|(8;z(nnilhW~9jYII9{@9oz&nL)_(@SltOEa}5{2Mo6~$db6V8ImJ~u9Nc2duy2{Xu@&WrP|Ed+GLmK)-PTNOdJVB( zibsI*H%oXrHQleQoKZ3Ox!YA{q6JR+)W?yA7C#(e1N6$_i!d%N&ydBq|MzFb7aOK$AvM|p@b_~K;(COCH}gC^~s zldhzIK2On_Qjm;@xwFH+9o5;#Y}FPSP?zzz$LXesj|GL*^vDH1+n4n8hlnlHqv!zFNNn)ACE!GyjyX?+0`8&&GJ64|R>K9_g8r zuAjTeYr#TbPP($5FIXhDos+IBFTds&M$|ux!@dHKXK0r@f9&7zFXk#=-n+;+VU}b@ z_d>5aekYb5q&CM~!Hg`cpUjmt$6OIN7c9HDI&mz!`2I-4*!}}P9lJW_m}}V;ZvmL$ z01h5VP!&4=WUiA=#>MIXV6J-u4cA9p`pI0yeHC+WwF|K6lDD4Ejs17YMTUWDw$H2R zRxOEbbIi3OLT`D*>pA9XKF3_+ZvAAgahD8xVdI#6f+zf=?|w2@Uj3iU^<$^S=9`f! z*>lWw7p`-TxuzAn^C$av_CA~fsU2%#wOJ=sgWj}#UTg&3Te;0P$qKoHJNlEka-ITz zJe*^$UBvA3C>Uu!dF&m_b$#au^|wFXQA~NX>$9$pe=^s^+u@~_-}?2+#L4r z8+qrW7lXi)^NYf$?3MF2iOzOjK-E{-(35eqVNd&kt~Z#TT@U-+mf`fTdiRMkwhZ*y z1XB;1{_&l1%e9O3<0Hf3$%Qc8?!`=SF+&M{ymR^9_iKOnoH0~7Gz`5N*Hs%-UDvKy zH*rz)rt~o(izdaN8tAT<;AjB6Vm9tajFS*gJ~nTPViRN;b=Ic2?S|8GAcXKDwcc%e zUPiY~<4oLVRVw25_iCeOZSVkvK1nnSl`B~M;%S5B;+vjsLaO-(QE1PQXRc=L*aPpZ z{Og37>5|Dc_eYi=(gVQuhOPmSQb`YvZhR(OzH~_KXyv|$ z8vnX?e){w4`i_1FkvNSU8J3q*?ov9|7*zGvBX;>(A>2B@{+j=~X7n(b%|SC`!P*a6=F4DT!PFcON&)x%>Ue=%iPb@b#xC zc$G8QXR@Th)zQ=ib$d9w&Zyg0YIk8P$G1$=Zr1_F?VsLkI=El_J@OI|v{Qi;71Mdn zokK;DXncg)g84+T&%OCAIekj^>eTlljQgQ2BiB^}@KTIX;0I$=z6qV@g1JMe)x=pK z1MCg=u3hL|T{YfTrk`WK++nvBqp{Y`fwHMgr$S%_-<=^J_97E&d8A9-4KlSgE)&_= z#D^3Mz&0QUh4G*U%p$Tq*W|VZ3{2;PCvQ(rC;qgouN>X7hhwPu6nbx!%?NfPH`@1N zH2N{kIv2j^=F!ITdsgQi?5o2W;;x_-PR4x4bq9M^)ps3|lxJ^Wb)=B;nc7=syknUK z%1UTWUQLjn4i5V@E!4w8ued`T}|!u2NZx|%@Yjc3Ot%1tCa z^ND%alXrhITNCYZpBGVsSB?U^Wantz8TY1^aQ!eBmH2#s>1a8pTEWO&7V;%)mu(CX z9}lSRTu|L~itxD{sQdlgukTtG%EcC5 z38Eq1Zo{#*Ulg~moqLkV_%c7M`R0u|$eIv0{XVJ4N7dZoRVvzBmbnONWLT|d5idX8 zMhlF!o87FoqPrz7H*fmZf~3AmJn+WD|3Zu!<=DfUhATbJF^l>#^L!(Bt8Q*hGIRor z4-(dLsy^#aYGzCwgmdizHGG4PVhmH$+`nqVkFw3YGEz%+eDZTw_~VecA`OcElYEk= znQ|GGt(j_>{wa}$5useVjL;m}k&ITvYV}C2vy-=}qg~It zD?R8^BQDqMQxKzL+BIBzoL*Q16iryW{+H}FMKv>1la)nNa^~4*1?9%<=pzHRZ8;J? zg&~n@G+>>P+L;>KVW69bgl8w+PtA2acyzi`sIIQCZ>2}*8gq@)C%vO%RU%;eqP_FG z8cb4Pq9!aZCnFWEcC;_w71Ts{q0g#lf-vuzx$9O;&?Lq9P}9&LIRQK0Pd^g&yL;Gq z3=Ow@A{BJoBCT8!(?&_XSl$FzkZnF?{_0Y2Q$Hu|PQ?3d*m3RQHoUBI{%j14qFID# zo#tg{aL3(wO7A7*VKwVi^Kv&HLl~+^`D^B`Ec~ElyDbJKTI*=qLv?o+OuvUCX<`fz zb#rOu2hdn5hpVRE(Bsnb0^il3C=xG6O^Xv4NgD>Hpc})Ca{^1*!5JPa@k2qJOjjBj z-UMhlF7+!)_E2~Dgn_qHXvs*fc|ebJzR&yXq_OU>H8uNOxIpHDxIzDAjIqz!<=9uU zPs9#srq#Jadxy1KN#x6PUoY=#s2ZvM4|=2{OMa^;0g0Yz8n$kj$FptkMW2fq(2$?X z+v?S>pP5>u&Z&?Ps#+y^Cx9pcZd4;o$;dMbCflFFFPyJu6XkUZ(4XZ=J`g8tfY&S zM3aQfZ0hU71Q7eR_|CGuF^I;g8lKyf0=6cGx3mBE`UrC+e@QaSY#p|IaWY7}H^{r# zSk-3c+PJsIq8hCV^YEGMF!M5t!t^U*cc(})=QU+vLMz;jk$u^yXWZ++M=wk5JDpm& z@lM6jf2j3Gfh-RXJ=Zo0(nK|vF!B->dQjpMEK*@JJqQI4Z!RreHFPg40r8kuZYwx- z=HG1Yl-13}$Ma1vqotr7 z;c4m6Zd z{q@DzzbNaFtaLGMulZJ>ZnM0UsLm2w?AK6>GJ3O;*US?7dJ8fx?fE5npkK7 zo_OlkH~Y#v>X)@<=ufAK9Jk!`Q?f7owTxMVy}lMSe^_Yw4??rduqaIH6f zc+hRr)-}hs0zug~oSr`xMalE;POi zjqgI^yU_S9G`DL-87l*HFBM;x!bnp?D3&Ybahr@fwQPP`n;^bRLS=P`rlXH59L*cn!sC zC|*PH8j9CYyoTa66t5w94aIBxYR=nDl=uyIYbu{U4~p+uWS^?Aow>3{{aRen?1L3< z{SwxY=98wk&D*?F-h95VF3K@mw|p<}4;{07{ryj&c#X05@aF9{o`*dd-iv|aH59L* zcn!sCC|*PH8j9CYyoTa66tAIp4aI9HUPJL3iq}xQzPkS_6tAIp4aI9HUPJL3iq}xQ zhT=68uc3JTU*a|Xe^y=#f1VA$GPdyF&xX4SBFAK_@Mv4#HqBk2t$PCo*zF$K_P(DthKe+1^WP(X4K zO`H>S>f(PLLvH_j3|YPN7yZwpZkGScF=S3~-hr+NeU9Wzw1P(LY{PXKZfeOm<4>TX-eV9 zJ2ymZSD)s98o*70eihkkflO%q?5nGOo&1}LyBZeOCRHSikvi2wVUK$G7T-&AN@*lg%534r0=}O5quM*9J#gDFqjI-8t zxl`9km@bCW;J_FrqF98nkK^ql&kP|PX}pl_lzRIbF*05|3v*m9@DNDFZ{|

&4bqo)?Bj-qTBV8VGPCTOisJsxa_|1l~2_K4jcR7{VG^4l|%_gEk>v8 zVaLc0e{Vx+Gs;5(B}s;x9!lZUT>dV3$ZmecsXNR9QdyM@FS;SqJb{yE^p>lB>-5G3 z4uXvdLk7I`T9<42*d_-(@MA56{#~{HcOg(Xs4hnu3Ed8#I6Wg?()ImS$b0d zRiub>wUhze5E#1TaD1)<7v^nNaU=Yim)nW=zp|N91eyWTfO4YUg9_DaceC}-V)R7B z#oEuJ`Xk=fyq@yA>aRyc?BE>pk%+Xkix#$|JN0JLz89 zVENl!fGK{Fl<#KGgrk5#l@w8%&nqP=a#J%tB$a*q@F^a8LzMcM>qotca|Swg8_XZa z4_qL}XC`pOIt4XL82%Kjwmsr9X*QLux{(t9AdqFKrSx{_im`-GBFIZz6X^wFvU8}S zT2qo`Rm0fF=yf(KV0e17zTITj|Gf%L@g5xehGo<2dax_4K(f9l%cX#lv-Y<%_*vym zn0tKN)=AT+;TxIstxQz<+_JU+gsGsZ@EwnxwT5|!#Z&RZiV@^Syx3!DaJ5~+*btFw>qik3(R`OuorRcJ0)8)9iL$_ zrma4K9-_19{#17}G1#)HENuPtR?=RHhei$Wb5|hCKzB?Xwf$nAcPN)wWAq96jIxJP z1Q5$h`LjA*3Uq3bOvhKrTztF;QG$Gs#EExT?_8Ma(6^hYU}AK;$tu^E7~K?jz?wzY zNkhmPF8Xc?k+d2&G#_!9;;-F6$WbiDnXo0zsxQiu6YUTf5R)v!k|=!H2H0hglqO35 zyc%cBh0#Iyj1pFL!7Mg~*j^ZxMnN-%$>~Z2T8g?HNytmorZU*hJ!-az+Kybpi~?8_ zhu=|%<6sd7DK<#S>{MV{v8*~9l}Oq2`3UBM+*Xs4d{jg@N+aGE z;nslEs7?dbcGc()s^@qJEhR2mgqxxW`HsRV0I^?*H#i92&OkM$5SPy~FriX1RXtsr z$WBm@e^Kmq>;Oou*eq!xzYku~2cKeO&v3oQ6XDByLd!A8Aua%F3qwS>SkAs!5iW$8 z!%HO{rQkey=>?l&gSZ%73ap?8CaBUb=Q=%Q!DoQ2oL31K<_4gFoVhhe1OTJZ@X!7^ z0PS1zj{)c_LNbkmtmC+ZD-YC5@ty!&z)9g@5s5LddE7l;z3|hb+=DgAe-A)^5F@1= zT({&uW}saZEEg_uMvA-kRW*_d$VNyAkl4@lh+K^<74M6s!DiwJ_kSk_G5;Kc=H^nB ziJh~lu)oKkkJ}T1Xt>J?vYRNaREm%6V533QcLhJ~gt~hN*1X004=gN}BP>&p#~5%1 zgBUNy%NUprAJ}(v(n8pwf8T?)y7lKCbX@+LKlh-^3m7PXM^1}6T1BKVF~V2mDlxvh z3bhBsXOfxZd0zQ`-e3~_Qbq^HG3YnPWC9$JO#>H-oAXXWOf3>@AjEBE zTDFonjqJ4N2Xi8r!KxI*Mi3%ah&xY*mK?k!jzN2t5&Ql-2F)xE?tuI`1dlz4z_PA2 zvD4OK&@A|^dcc;Ck!Qln8EzgNAX*XnTLMvBf_^S8K~v)Y*Cl9fyg{h+e@f6m%m2Ov zEwT>&Rf3KT$RBt`eq>R)R)S`fg#V`mty%KWjIpwcmtMl36_=o&|GNYodB|brze~{k zg0KISpuglLFUq!vOVDFs;u5rT^sf>$ugr>5r8|i`$=NC{L7$mjD?v~HQ-UU~m7x1V zueuFXQmIsPdywX=CX|A$P{NGx>|05oaV8@-4z%7iI6>IFf$Hpf)P=iq&H?# zKpHUiq;39ry!=#n#VF&(CaPs+?Oz#aW;I+|>qZhgO^x9F zuMD(S$$v7?L;szDrdBJ7GtiuRe^O(=puX{+40L$i5`z;O@b3&XEA3YXI^rV@XeU9N zuEGYW5F;x39>5FlaO)6)&F~l>E9?Xn8Z`oUrrt86XM6Cn?C#=j1`xJ-=^YriObr61 z0Wc&5+fD^o2SGAas51$=;|Bcvh?J2KtjB{`@ui#2-2G1mI>oK=Um0lDZE*(r#5G`4 z^hd5~fj9%b_)i8p=#PIg&~5>@Cd3tJ)@}OgKN)CVON}@KO}*vMdoXwAhByP=CeA<$ z8e}L{+giZW;tVvaN}Pf2L2N#J=K5L&nt#2}P3`%w4D^SVW^o3(^H&CX{KL(0W~-vX zS_WG7pA592qKnD2owpvvtkGzx40*)1`B%P$(4` z6Tq1&U1Ner4pb>;e)Eqf?a>UV5w&?S1j829milV?s6_bB;ixJ8rxR2Zu*B|^%I2(^#urZV*|9I0Iqb$0M1gOd#pO{iZjp^hn^I;H(DKm^4!obgQLFX)M zSh&~)sanp~019v-3F(2hC|l@wH01R{0lLYTu!nO$d0^`j@0EFJyaNYj#d3)xWySL{ zzDy%8P?DWh2d(MPzLS#!8HidEs*v*fkDoMyo47~#hQ@g!jTJ`L~AYkm=D;NA4(l2z-G7iF8hWlm0g2sr{Q8T&fV4257&}x+C-7G3byp zRfA+?K5%6iw22}#2WoX~gmHd()8ZI3|1HcdmH6}7NOXDjFK0fpwajzuk8_~QRyW5YjF(v_Q&x>I&|tCa)Ffk`_^Z3M<&FT=CryA`~Z=s z^yexOzB^JqlVhS2e}5c+4V|+L5DM^gRM03WPcU*T8QD^espUb;js8n+k7;i?`Zv8YpIKF*3Z<*Tp z>eIht&{=b-V|R?5rM4dZt0(e}I0jwx6t|01QZ0@_k4@{>SC5Ee(CwYGnk9(er{t?d z;T@>hWI{{aofT&I|L8#rw+*hEYN+6}7oDV*^k2&L2=0q}(D-B{!?hmt2XPNNXJD|P zZKvrMis9&F_!rAemoUtLxCiZW-#H$iY)+bc&6F{+Uh6>@SZO%N{Hq6TzFiIeuw$(U zO`k3SYROvx%w6Y}?tY6toCD4??Gw&U)8WpSr{W&8=kLm2)V_&((EZ{bG%&cyaL zWWTy?ywvvPkRidCed3qp-$ri3#vIeu8OKC5;9NLIXx~*!xmoI{^D^9NuYvx34^=Nn zc~_0?^SZ!ZBu!5C)OWISX$e?ZR(<9}KSap7v%o-=z4S`PN9ldfW;-o*eLp%{Eu00N zhqlaUte1uM6)py_1mk4G{%ymFeR8QU6I&t6{6&4y;6~tl@%Mr|0eMBl+FdRkcTzk5 zEQk6xAYOcj9_^DaoK(vGaq=0qrFbdmNmVz)?!5f6&8TpD`%7GcTVOdQL~3=S&5fun zcpg-_3BM@-eY^F0`Q;65Nw>*1{$_jZAiIR&Ps6GnM%~b`Np3OkK5~PM&a^!^*47Ml zI@^Du69v`xwQp=5hJxcO7y4&TQkSH{pmBiUlg6jzJ0aR4_v3cfpHUaIYDR|zVRopQ z;e%W|k#{IHDVWEPt#UDO2T3V6q!Q0(2%o|RqAEp>#g%y}g!4v2oc8mZfH|Y^$KwZ5gKRZSTPp}bk|iC#SMxnQcoT|FS}pFFzdXBtvr=J1 z0@f~H`eTZcK{?a)Ec$V=w91v_1ULH$@^d|ntticlbQd6)Zr2`tv3x2j%1&K5HR_9w z+P&9RFfYa&{HA-eD2bq=Y{xG;!iv(qrm0J3>DN}9gjXFn`N6{$!8|mEL8S7fu4$$! zg~}-WZsx1Lx=he`otRfSk0mv+Uhr^z!pAo>TNgE+x_o>7NUG@alOCyKj5iKW=S+T# z`9-Nl3*(gv$e>}V30`{aj`n&ggxp|wxJ}dO%moF-)5*uUPUvWbF5s-FRYTpILXMTG zF}&rXd>FLQse9&Dkmt|T?rm2~kF$IS2W=Wm%rPCW4LC?O7?yijB`34Bcp z>9}_@q@`z>nO}4Ixmj56(v@2{r)y86TsFYtfU`^uz9O;{NY=-QKZvS|5ThpxK#) zici#~bwkt(VnN?emu3{dj^6;y&M_7wZ;aWi?Et2?JD|PE-%c0U%mtz1{HTiQlVv~9 z*~#k%v*4-#ZT;C2gyVazZoyt1doaWFdlgr9egcGxnvZvFBH<$_2(1`S#ZDY&d%n2>8&KVRs1j>b@f#S54w0C(ZN{ zrhAAD07AOgK6-^8_x`O6;(T{gL(lQKAIJ1wSPEMKgDA)CQ~~bzLI~v9nO0aV!EEMU zoBBp70FD+Jot%5Ai&Jc)8Ist(_drsg^KSG60HDM1S~V8YfYn(%un;VVFUk90>8<&q zqMW4m`o$-R^~G&Q-Ewuw<*{VNSsXN(W;KTZ7&T?=?VPr&s+HPvwItQkd_c-q82db$ zyT{MOj&R*!PC1PY_b<~ShMB~xmfU)q1l-D%rn4;3yXh;*= zK=yRP9c)MA##Q4kQi&#Pdmu?Jkqo9L)rS~NL6uJeH~iiuBw;Q7*dT627c3jYAAgE6 z9JTK#@ae&?wW7b2+82C0JGJHSy}w$~%hq_?zu4Y6;#M?tN$};)ZxOB1@tX7WjzZuf z)*AWJ?HK-21K}jdsA^xu;dQb{%ly^NMb7HhLX_d4$%}&hx1fR4K_kU@>4m{ZSYENS zwfmxBWL|v4rh&HnK@yq8^V)IbQL@7vRr$&O@7R+9=p7Nm)rah`X^F>DCf_~t*2OV5 zWid8iO*->#OzdtnB{?@VB<>KK?-m=*eqhZ_9NXlA$__&0hSGW$Eu813?>j#_#_)%m zI|&maz_EdBO+EPq8WCEx*^3d|KYbht5ANm|d?TrDWyJ1LZu9SNageo{5C3;7dh)rE z{pD||+P1VJ@hz(@SLMS+R-5;zxE1YU#eL~VEs2I0)^?0#;%=*GuK)V)R`ecgmjuln zA}4YAI9TdeEBeIjLMi$>>^981^+`Yq!>q)}JrsppC-J6t8r(R<1I^X~Fwrk3U z^;O!(cwZIvILVVJnFvL6R-X&jUG-h*D_0boMzto2ug-3-mA9JF zI^0@3SF|2{dc+1=#?!A_U!r4hnhYH)t$WiF?OeL=Q+v0EmGQp9s@6caKr)It{PFIF z>u!Y-^p&75^1(8JeXaq-9QJ#;m7wqcYxI>gmd|52 zB&WHJx~%IXwnMA$or8bhr7iWf`tMV%prY(PQ+`nU`>da4M}*cfZ%?<5%IHJCg#+wBhVkXlE6rJ{1MBT|^GWs@ywEORw~13A6m z_#JIY>*LPe1t9anDr40geeZog;vDbJe?D`QI1GL>Ym8a7fCL}!xFoBk=$JO7Rj@^6 z4&LsH*2TY$&;OLJq;(1Whl^T$Wp_mkgWKZ*Cd5Bp-rs)9TS4{eq_J6rRa}=$#cnfO z;j@zzZ_SH$`=4qZn{VxPd!j5-Ef%@g*N==<`?S4y!%vgURKIlfMq>Te!<+1gZi*m? z6E}YMAeG=5dhOHdkm&ZlkM^LIJhYq4es;fxlUsORf|(+}P45<6CUC)t7kP@?nZ5xV z7X>z2&uTl&6Dgs)9Z5dn*IxUz;;)z%*aDm!B4hFt|4i_=y~R-d#qb28Kr&OE5&-_J zwBhI@18%E#u4JZKGE*&?sg}%COJ=GiGu4urYROEsWTsj&Q!SaPmdsR3W~wDK)smTN z$xQXxy@w<-)smTN$xO9mrdl#nEt#p7%v4KeswFek|BIPw30_O^8mc=}U8C8A!n$Ku z?_5pJ&q(q^%9Ac(osy3Jog7tBvbf_$hwCC@7gKv=D%p0t2?w$yna?I4gjuPfXkY#2 znr^;rt;}1Z9M7p#yyUCLdzqn-3eG(K!6;=q)@KK4vXTmCf#OuD9?DlTV>1fUY=cKAdM*`O)`yUYx2Ym`{6j zQ9-c%qWIkuuFMaYVw7)Qrp^K_R)W_mzTzcpP4N;op!{<@jcJ&*?Uu=GA+3fFV zHa)KVRMA0yHVAxRIUL%V+>U-`2a3>TMJt>^p~eLgypCRpYIQx?Xf2a44&+GiT7uUS zyq4g#1g|A{Ex~IEUQ6&=g4Ytfmf*DnuO)ab!D|U#)35)O;I#y=C3r2tYYARU@LGb` z61tBuKFKdnE2FgE;Wy#5F30~hzlzqU=TYbLWc9=&Smw(;xvFWJusSn?t z$#PP)cW+B!|FuqUc@(FAkaVZBFUd4LGJ9vp)2K~4VYeNJ;gLxfi*1Tp)845zNXHX3 zcHoo7%r+QRTrSwbNgp2ZlHj$OgERZQ#(G3Wz#x2!M#^EIU{t0bYCtf%JeRD?Wo2lXem-v=-gi! z=SS@+pCx$RD}+#ozy>UtB=VaR>+qybYojMv>D5pYc#59DxKSA|C2Hp+@9D9oj9VP? z;^R)<43?8^g|+Vf4$2p>q%1Tte^f~y74-%U#U_@g4fE>d>q4p_NyB0BEf43UQ6&=g4Ytfmf*DnuO)ab!D|U# zOYmBP*Al#z;I#y=C3t<#(^!Jn61|0oyi|!@rv7%@LI0G z&ivj=i|zUycG)6gRwWNIQFpGmX)j>jRU~OeOIp#pSgAhi6n~2-X`J1(rM+4tg^rJ} zd=!~h>yq^jC;#d3$i^nmBg(uRT^8s`bW#t<*E@}&Js*@Axya+GI5P~H9mfP<-UV{C_7B2k@ny~B@ks>Q{w<@|kO3!HJ32dG|); z52*u?}zO3ur{g!=~YN25Q3s(uOA3t$&#uD~g(u$U}qHE16xzKRM1o$;UyhA*n z`%yqO2xh}hFN0;SN?Os9RLSD>QfK_jZqK*EdKQBGu8 zI+LoO3n_H@q-EtbRZ>{W!AvuO+BTa54z)RLN~F_L*d)a^R4lcZzg^|ey??B}Gwm?m za#|L#J)7@aZ?XH=#`fyflO?}4w*6GyJXu*qR}gl`w@9JLl(?U#DQ8gkE@!)n9y`_o@WLfvbSa5yQ%=`opd~bZ3 za%FIyFLN%R0tCWFGTd-eG7`)2#u6&A=9dcNI z%0f-1+0diH^~rWue&+H`@AGJDd&>p^8#{S4Om`;FmgA5Ts1z&HbY~xGGa+dmHvv55 zP5m~Fi1*apalTZT1g-%r0)?b=lmMjDk+BDVk1-NnxsRDOqEpK18X)JHc9-1uG2 zD`oZ%$ioEy>q5Gu9IubjBhyr_k9qOS9mS_}K~A(b{ok*UWz&z$ybC43EvTV#LyB+K zVT)nDvkmI8vAW>>i&>Ei+L)cmde|nq2U|^!`7+sF-^}-c{hSu&9wPzw$K%YSKplHSX9z# zSvwMl4xpsYlYo5XG<*}5l6u1~2Q$Q%G8oLwF8)#Kv#T3tFvLX1go1DVRP2O16es*# zt)kv2{PtE}Eo<|JYHhV2CLe5uUm}J)Lz)sC~(2?lFLD5)X*_CgA zE)T@^r`i$0c);-1RA2k#%`N&~H&V*{(_}xh6y7$oRrw6Km3A%i#15ku)F=$d~Z?3|dfRKu%7>cb3=D-DrG!-MA@%ZH4ZqB9MT_>1)|0&86nq=8 zteGYC{SDla9wZ;s{K!21Ui_9p8nJ=rI5iB~ccDjy>^)uo?HM_Q;Tgf|ng zPVrg!$)w+xIGXV;0){BAc9S2aDOBUc$uY zI=<2@B^J3mWb9HNOSugXCUR+G(%YkL0%|?hzo%|!GgI~1GK2$lGcbO?Lo5WKw6nm( zhi!kv4=I28OXF2gYkV2Y@Rs9-4GR-5UAMPz6|m@ab9Q-(uN`gPTqdncJf-vJ!EgEd znSk|B0s-rCk7CIEySZz03eAEVF0;Y13los&p8Z2ZjLPYI%w*|oD-;2(KKuSa8 zg)9S;tPAcg_DWZp!A_iqnYpBW?i;f(t5_pZit%1M_37;o7r%kxobHu`=!UM;S+Zd< z4!rmLyTvNY183pJCHTq9F@_YDAs071h1-A8W&=mo(>#ny!b&k?rk!C|L{jn#Qdg)j zSaQsF5-y7_dsuYlBo{s7UdxZT32ODuu`2TJsVKmZV)gxZ1t#nWYv zGZlFi)<}pclmwdMAQu3zBOldS3iF&s)zG0ND#C{oL*bs2r@+FUQOm5@zh509wi(Gp zz@@)nTyIOQP~ah4oDT(w7vMgY+rE5<%jbl@t&jzg+&@u(Auh(zXP2W8sk|U1!#}^x z85J&srqN>w4A7a?ouu1eKs35$cO2~Ry+C9w2UL-a5H!?8~_Z$ze#-k(Xv9g@tGn-`O87azNLHJl}86l|I6q3*l+9rb5;FGL< zP`B6w_e(?^9f-OGGpL zlsDvMr&++Sya2_CWLPA`iU{t=$qX)ok#}^ zC;}_uG=;~)+Hg&x{jBF8X%XZN1LR9b-5!J@@i8jPwa*a#kd=eW7_|o5#p@NFRu~sxqA6Fc z@I~sAxUZ3xZz=HSGX^UH=u8>Ri34k-c=l;38xCcL&A4UeWmMz|PN7NU$_1bG1(rd0X!tNWQ%m}q!GC9y0~2Z|sE+2|JSto} z_BzukjaROF!-ME?!6Q`2@q0;8<*+??z-O=a??b#ep7iSuRd z5x|Q0ihfi~tTLgtq?<;^LFcGIE`tY`hK&j<{OJu&OWaWarecL{WLC@Y3XAW6?XCex zplHz^MMiAyT)d`YETcos|KX~p>n}aP$2c6Sr8AN0Pt-ONq^-}Cj^l41*T>3`K+*eE zjGn>uISoEH;7OCT8j;Loon7p4bncHxIb)eqSGfUkV0k8J0w}T)NcmG6wa?UgxZQry z-IRX=6hXr3Gj9Hztr+EDhI@Q%sX2k(U>Xxn!$Y-N35xTwX*bNtO<;feRaQOb-Jv@^ z*BVro(2Y!_0~LVcvFAAV9xG!Xxk2|bp;KELFW-PW3Bi9}-TD%ba0v+0dDarT{_e^u z0KI{4O8*Qxp#e1$mUjrGu!|KBmL6zJ!#-O*w3mMPe5sId$gxHw6?@I%0MC@hi55yj zE9@TF&f=Qg&`UYjN2pb`haTe55BaDYKa`zS1z^QGlW;tWMh8df-u(!HmOZYSy7s_o zZ=D$fy846v{X_Mo!%%5A^iZR#0{TKrjs?o@4`NpEJ@dBYxZGS0%=wP}{W4ew7mU7( z84*a0@OjuLko!K{6?P-$QQG@H-W54|l|5N1^dE976kCIBygz%^zW9d#!ttR9f2vI=o= zV2WG8wMuwd2P%isp;iVv{38h>02hjAZ@KAlEw-?{)@2^O@K#x>by&MjR|c_1NlAJ_ zbbFYED`fTLwnJF%u+n8(fCvh+K&ttm_||}~87tIDt&xb*0bJz5!}kZ-&LEq#?6X!V z=u>D55*3!mm$t8g4Fli|R!ko2Np3r8ffExZM7=JBLFfs2%obQ)i;kbyk_bT)?3WvW znO;yFt;apvZOU_o`tu;k4)7x`2v>4KArCP-)sxo?IlDVyb_$j#M3o4UvquE#X5EVn z^tAwGTLP5lOSpDgnOCz{d#~A@h0Y@|3y4UdoEH-kQLz3 zXYVn%$VGS~wcmSjiQ$A(coVAK=1fzHKQX*=kQ{Oi=zR^^#C>7TDLudEMN4QKGw==h#ab8ZCU(^z_G#BgG}AcvLY5gW`3j#|Ara;i&wr@l=)%9YW&wu|g17 zk0D2nZy^f@34Idn-T~_#qP8h=R0&(zT$i7=;XKE`=MlO)>`e5rbkVciQrJE;sGRjg zm4yu1%Fe?V4GU3L+@Ym*)O6Cw?Nv>C87M(@2N+hP_+*&;@%ZZq`|8UZKm(%NXUZ_^ zKElj}utE}Q*wE>oU{n#Lo&Fu1@&V`LXzIy)OTE>qO$F;sv}fD^(HU(wpnZ)6o=Z1z z6@ou+XJ?rtH}0h9N9`j$1$#Mm_Ef-Gqh}OoW>aRk>v>3t9|U@bO-HGcs`7`LWcj zKSG_PF7{6DoE(^<%YN&{?PBEuo`kKmxB8}BMOuZ7*N66Ro77qTJB}Jh8bG5NQ-xF*o<0Kn^`cM!>cu2A!a&$`-1H}!&7ST_ z!r{L@;kDSLhpRTPy6v{UhQxglknBcd;yptFkl>#?#oeaHf+kdY4-dxp{6lkcTkEfZ{*CsCeK^ z&WPDC&-t(}9beo`Wm|-ktRH9@n7GxK+_WW8p5qF-CftW6Ke;G}LQuG@Jb!}yj`asP ze{|o5)s`8NPa;?SM}~pk5AcDrFNSTmB314?4{>4+jSd-k6LPfvTEh3(^wNHQq3FK8 z?XT3giOSkU5wX5Jx!b?=;4hb(Y9jNx@eeaf#4(xO9m3sn&72Q~ucQ-5d{p&lUo8(w z0>CA!%%7oKl2N#;>lg7xUV6cQ7&WzbZrKL-NdFmCYkMp+rq8H;h51c}068&FochBE z1>ngG7;Qg+kQST2th$Zc{ zPHx_DqxI%)q?*WCyVbu`(P~g|(r1L#;H=do92(#89PCv*%dOB*!IG%5gR)OH_FX>b z+2l>7*)f7*>XuJfxrJ2fZ;5X}pYsl>f0Mk;a-4Xj^g>{zd(9^|l?^pRSC&{%q+BX= z72lRHv7klu&rB`0E}X9SD*NaVwry83*f6X1f&1=dW4oIQ?1x9FYWw1>IkDiEV}B>i zs=fZRzCL<9IG%dDQyJmN3(^PM&1k1SU3xvW;8d18`!yI`X2lxP++1g4p=AwwJdsqR z-sj3UxqXE0S|o3BHpAlB*AEAB(z#1PEr8bvse|6mzN`wuns}*Eo_q}LJ3)T@?e?KBw{Wt#I-p@>J`Z_4Q$$VrM|e|pwZl{ zJb=RO_1eBgBi3Sf&cJWAy%%}KNymP>oQwZP7%b9=-l_{TNH)anlos6Z_TP8f&p}r? zKU-es&`rZM1L+J8KH^x|J5Y}F!v@CgO3&oZH`jQg16XC9x%CfEp8u-t8{+Vc9axDH zO#x?HZ;|?9`WH7d+~Cb3R2D$B&{I7wUQ$Mb-xGqT7d4czTomgxf3DxQ9NNt zurBL47)&1Bxeo{5=}HI>sx>M|(n>bLCKyb|nViUZcgJ$05md>&_`=>*O*jXu*u-VX z>3xCP40@2RR$Q9^T?@OEUEWYF{jC_NIdN;>r#l-3TwSN*oN@MfwdwZXg^wTHdL2Re zz9FHhs}o>}?_QVZBlBEjbadZGNjbO1nL^do%9VA)1vlDBo?#}d2Z`JJ?l99bmwWUh zhe}bv2M71tp+x-E7hP&Q9BxtbhT<|^gU-twY>QOe0%+t&@1mD|Q(2IYS%#%(_=y zir#uTrVX-FHi%)h#aYWjASu69_YWF#Z&6_8lK0Gf)U+Bq!;c1*60GIo6fjV)-EW)-9DA2c}nAA!}u8PIAVjFN)YIToqr>ogxoe4#j-ubFWns4j*n_C zZU75$MqlIhS!Z{tq@I2fIDZr|qd3uyYAxNc8VbV8=fT^S*-0^s89TPfd2_LUu_E>93&)bfHYD)3+=sQ9Co0_z36c^Bq?wMpkQI?mUq%Y*8D3R+<_;Z zgfetI2KXCX<{x6G`}}IH^pMa`_`|RNBlU0TNhI%6x*=4yJS}< z=LfJ#zRFK>kOfW9lXn~{wbC$QSht>S+%YJ1D|A#&P@Q?isY4|$Do>VP!jmp*!#lbJ zB|eMxD`&K0SEgrS@c1Mw|H7(sB)4tP_is-cngA$Z-?68}S4MTgUPZpt{-DR1;b)&i z31E3RNPzp5*l9qAl3;Hb4}mXEdWuiF71F}DW_4#d{!9Y?t){ zx3Noh0v}kALjMxX#e+%b1J;LkjNz`IT&L&yB^EQyLT;DUu(ft^{NPQwlidMv)J*Bz z5F?u2xLArFNaMl02X=3tfk5wO7Z!SqGDYVITP;#4X)d%8CNH#cm^<|B-X^5E#sXNEw3uItp7_C##{(Ka zphy$RQC5j+k|xV)nxcpFEX-E7l^xPK?)o-J$B#8wxuV!Ksx?u3b#{BLyw!}>;nw20 zqV?d@BR0@7o_^K(5*>rnWawCF-J6zZ=hA(j+PgihjQ15*wFbHcitho3Ki=JN-K{W4 zqMHAItETONJBEb+6V(J(SNZ=3s%bo{u=7pPh%2{>_(EsHNlU5W!S!2XR7h#QDyok> za~pv^7Wg@x3Gh_Dar!Ylva(Cnvwf4O{i8A^UozF&+gE5 zrcyw!lqt@1TN!P7*O2MdyKz?RvVrlrEv_kwdX=lDF}>b}YVPl~9@pbk{=HRf;=$U) zQs31vRs1&Y+$DP$tHF#(E4W{*4jB zJYW$o@2C4b2RpmN2(oR<*=#9&MLGDcxCz@#Cu131H)M)kx67O^(kLxnz${x)9i%mD8{@Dyaav=xoG?ON_G}y zJfzR3{n&3B$)j)HfeFbq?ypYg-TUo;PM~>~sk7VAI!3Fy5{V6FF%zx2gR~>KA0~pQ zafvmPTWUXi(l|!PqRiqN6hzMEk3;pq3lN-pLgj{^i0(_xlVB=SL+B9X_iS+jC~gkg zw5$QSauS6dn(op_%_ipQvSi-5bZR^ku{U3Rq245f+g)l%wS8=c-Q3oiOvxq^CJ(E7 z$K#Pkk9|&ra(Bo!kJ+dNvCZ?oUUlzfd&V5xQW=S7n)thTrI!-4CaJO|_Rug;o^qexXu2`o6;7$g`L%uJ&N%QVxtx!Rz<$3nHjVbLx@mFjY zMGy!xXmeBEUpAVQ_JXh4`;%JPhRb6t{d}+#r8~Ydhzj@Tamg{*Qc!R!&Q+bI-sAC1 zkB9$V?PM=lh2yyXcoy=Yix$zB?^5&kyi8fzjLxmrR+x=(qWkp3Ye7bn4MULZ8)*P@ zoP^3R5L&e$e!pli7^i~ zh(3(J>pyB_y2y6+s5it(Y4VR^(B8(yl+lwe;$O69@mdBhu@4SY00fmPOG*MXQZ zj|7}XuEwncX)`n2g%GGC!*RZW8sW<;L6At$mLg0XV;4WJOxV?a_uLq=&Mo+qpWn)@ z+fwIygV2lIHf@psrxwM5zZAhYuy!9QhYE8)DFT}sygCNuTZ!QFanO!)mfjt$$TUV2 z)PM_0`dxTZ9buQkNrFWO9#dFZU|UxTkvq#SCrR9GkKG!R31WJgiK^w9vjdlGePo#vwz6{3(FM#3(K-ztznt|zJrS40JW8@ zoJ?55GH%R&u*}g{89T)~z8RkW-&iI*mwgHuH|Ve>i$&wXevbp^a|rqZDQ`t5Ys&F+ z{4!4p$##3ZDza*ol64$5R(dE^K;Nf{Fjt5*`NQBvYfLW3$oTyGDdZQVkwJ@`Xyz|WGi~Q?j-IcXRBDsZcndC z+53N_3|Nyg*$pvnS!q-%)!ZJmXIc|V!A>Y*MtJtEB+$6XH#ZKo%7(={sWpj^U1cyc z4s3$Kpd{*zjk8Dt#-6mzKTT3j8DAJBWsa^gpn8nVTzjlMEB*Czka!+ewG>pxJ1fJN zP9FqyP$6F|(AXh3tj8jeZEf65Kt-V0$re+m6ufnzNG=>nh3GMpaw8xs%%~+IT9pYY zqoQH~PLK~uRS0&XWco8@R`{vWJj$miMeGzo_5>)CDW&6Mx~CZor6|==foN)0G#73r zb{hdGnTir3=&D@I$t$qTAL!_Hnb91Wkx1R=4sM%ssvJ#mv29~=92k2FO6P$=FV)tV zjFkBwCbLF5xBSCo_$zBnM!zOzvY>5{y|17Ff9H0*WXS&CnQWDN=3h<*T#4pi`^U+w zc#wOPqOUy|D=t`%hcRR1XT8Qukf3`>*v5mPand!U0AqF95=%C?6&{%5MNkbL>`{P$qKvN+Df<3AzF!UoH7EgrSRyCg{?sx}bi)WPN%Gk^>A@ z+Lno!%($zi-2^Q!aAkAB9 zU$VIxp7>uRx zReWgS|4e1fYV)Z^ush>|kK-1~`aWEw{odrIhqimoP22OX`Bfo+zZhAl9nPEr5#F z6Bdr}Fh_ZqPsk!`uG{C;i**T<0;>1=_5gy$2lv@w@(Kw=XJ)bLk?x(4(cAVHuGWR% zYlp_`EVz~!a(W6O_m@OQdKKbk0syL>-bocxek zN5O_vV-|$Sb7w5A=}kVYX7w`IcK)#(A+4O=0^!)r$}=XttcvO2^F9Qd{qo_Fp9_v;B7ef*v`V)}_XDn-2IKg+RTF%x03NW3BynwQpds&Hwd%4L& zrFIhbtTKv|2evLT@0!;ibl||Om@bj{6Y)TV#T4=a{%G9DZEJj!75r!*15ryt6^ibC zSfYjAz&#S?HqH}iyn}M{Nw>Z3c-7&=T2|!Tzz}O0^&uF3G?H~sjAbDezpza3;Mw&s z;O~1+^sVOhqk0f)Sf(z$hGp1gi}xesQmu*=e$DTZb2!AEZBqYr)C3@L!e zT*vmiO_O7?zZno@<2$!P9i$H6qg?AAKh;!3zt3>#&NcBvPiH=Y4H~^D7YZ<_8z|&C$ zBcMD^hgTBvdnKlp2MNDtTO&GBbXMO)n}#1S*5TBqj$KWEW)x$+Imt3q29F7;b{-Z! z45UK>g~$?oZ%~JHM;d|J#@HyhzQXY_n}GJAwO3rh+FTPY{R$-jhP>w5`K0H)cHbfs zHF;Ja+pQpLER#v^_8Q}KSGV6eT~~I=jwCu_Qwe%!@EG5Um99?%8hUBF$^x#zN=5{Z zU!nbvK!*7i-(=cx?2S4V1s%?rtd zE;c;bP%wo`2j@F%C1$^%9uM5hDlK$7p;+E;?E~$<-lQ1^J{|WAYi#+Oa_fOZ=Et5k zVcpe^d%Q|&XmM9|8m2Z!J0SXZLRRO<8(OauX^Ni31w@nXE;=}8kbDYwHAx#xiMAZ3 zBEk(&D%+YM+>6oLOiQ<}Wznm*W`xK0qS~^pRID^~I75w~=V_`I7x;nzI^^sVdy+`% z)e=n=IGUTAC<`AljtvaG`3uYJZ(~=R8=ZEY5Np|mfF`k)1zxiYJr+|C6R&(==HZ^m24f z%dX$-T*I>VW?F&Xs3mr_U@M+`?1t47F_ziZ;Iz-aUBfa?1nBQ0=$~s?)-R9DO(%SI zBAl;W!?J~+|H86Ziv~JlP>f|4=eosMwhj$C?B0=a(;4^k$OhW^{-`tiKjLf$MxBW8 zwh5~??_!0k-HQ@_7R|~c0;ozj&0(9oQ92S-Dd>ioMFIM zk?#mu&J`LRFri9^2vwROMa>RpPk&Y=Y@yh(MRu@EoMIMa4~gK;7bUT;r)z0j5xcbk=ntch>mN_f7(LrWhkifY zJXH`Av2x@JH8zcRwH5-+s9+i*07(AEeTvG))W06suN0^tKN69FZF_8WcL z{!j~uuSW$hZ8p&H`lHv+CJmX*_YMdcHK_sOP`!tOgi?auX2?IB@>wp9YNO8{`?{M zSJ2==ga*6F0RrUAu@ZM?#G$~?;zf)ZHEzsE!GeWxdJ-hiqovgLGKR=EfsmFy&q)C;YJ~aY|;G}vm1(u*$wOaIO;Th2c zG?tDfdy>bZr#1whsM@yR)va+i9;gX6fswL#lk&jyR9~N(ZUvu+CD$-NEdJ&|0o#p- zUdStXczW8xm_QwZ1sCvl;BZ!t{(dkf>NxUglmq-;5ePuDW*s>+c>b)BLjPi~dPI)w zW)k&j)lZ`id|kYNh1s>aMyN?(oL#ZMPg8!XXl-%q|I%6T7vXRmPBr^z*4C_p|7VzK4H2QSb-Ab%Li zL5c_dd7zKdRQL}v2%L)P9M=3v0YMZG!T^92a&Ym*beQlVAt~l~hL{iY;=vGn{L+Vu z>rxc*Jq$$iCdaWh@#Gx8#$ZIC0)~__y8z@%1WBYe0YSu=>@h_k3xt_+Ozb%GCy^$w zM2UwEK*+?e78H51y$s2;Q?me45aC@g9T0ucHDn* z@E|2WCD;~^D;gQ&4LVwohl&>JZNY{&#%SbV>FmKjN*fG++K=FE#Bupy>5 z{Bf;gQVVb(lP5w}=@XLQn;DdTJi#OrTC4LX2A)YR!vYv$qW@wN5FmJr=m6e}#~*Td zc*4i0SYRY-G9U0^Z6DZqz@Hj?d_x;U@DP_uf4Jx;I3MMi<8HLy%W#NvB<8LVAD_?y z5DVr((H}hefr;!u{Bb;R?9?{%VV38>!vGdu@ezc6$nj?b6koU?n91RM#h(`tK%fT^ z{$U4msva0(TMHz3p)+8L2 zY0<$iqDaXNxYM<-Ex;^*A|w<~q75eMqXz!yg9lup1wcWPkS~HqfpB42+Sma$ zfCM=`l8+9P@XaRF^OPE-1P~YSM~3voh(zo_8?&V44tCH42lAkGR49b1`mlf-$kLGB zNJS8%_5z7js7IoFf&&dO2$X1pI)#D&N`i5LDE~b`KFJhF3X)-nlW4(+)Ef>r{lPJw zZ2$od6NoYF_mn4k0~Fk`zz>>mq<-)~6qpF(B%sKF0~JIJJ?KF?dcXvz86*ICLy0I{ zCy)yKLj)MWfG{!>z=Evv6&-v+vzow4f6Ne*k^+Tq^7$LO)7j%&it=o5{355474b jcBs_?3!oGtXad!|8l-T!dVv&*8o;SRj090b3J3r@AnA^X literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml b/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml index bd3d9c9e6..292cba7ba 100644 --- a/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml +++ b/ground/openpilotgcs/src/plugins/coreplugin/qml/AboutDialog.qml @@ -57,6 +57,17 @@ Rectangle { } } } + AnimatedImage { + id: opie + anchors.left: parent.left + anchors.leftMargin: 10 + anchors.top: logo.bottom + anchors.topMargin: 10 + source: "../images/opie_90x120.gif" + z: 100 + fillMode: Image.PreserveAspectFit + visible: false + } Rectangle { anchors.left: logo.right @@ -76,7 +87,15 @@ Rectangle { Layout.fillWidth: true font.pixelSize: 14 font.bold: true - + MouseArea { + id: easter_egg + anchors.fill: parent + hoverEnabled: true + cursorShape: Qt.PointingHandCursor + onClicked: { + opie.visible = !opie.visible + } + } } Text { id: versionLabel diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 9bd98c1df..6aa002df7 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -348,6 +348,7 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() } for (quint16 i = 0; i < ActuatorSettings::CHANNELUPDATEFREQ_NUMELEM; i++) { + data.ChannelUpdateFreq[i] = updateFrequence; if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) { if (i == 1) { data.ChannelUpdateFreq[i] = ANALOG_SERVO_FREQUENCE; @@ -357,7 +358,6 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() data.ChannelUpdateFreq[i] = ANALOG_SERVO_FREQUENCE; } } - data.ChannelUpdateFreq[i] = updateFrequence; } actSettings->setData(data); From ade59ada9ed600720e234e1ca97b5fb6e429faee Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Fri, 22 Aug 2014 05:16:00 +1000 Subject: [PATCH 050/203] Add servo buttons --- .../openpilotgcs/src/plugins/setupwizard/wizardResources.qrc | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index 218840334..2603c99a1 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -29,6 +29,10 @@ resources/bttn-calculate-up.png resources/bttn-turbo-down.png resources/bttn-turbo-up.png + resources/bttn-servo-digital-dwn.png + resources/bttn-servo-digital-up.png + resources/bttn-servo-standard-dwn.png + resources/bttn-servo-standard-up.png resources/wizard.png resources/multirotor-shapes.svg From 6904ce4614b4779b9afdf21640282fff9dc75fa4 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Fri, 22 Aug 2014 05:50:25 +1000 Subject: [PATCH 051/203] Change buttons, set default to standard servos --- .../plugins/setupwizard/pages/outputfixedwingpage.ui | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.ui index ace236fce..bfc0258a2 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.ui @@ -72,8 +72,8 @@ p, li { white-space: pre-wrap; } - :/setupwizard/resources/bttn-ESC-up.png - :/setupwizard/resources/bttn-ESC-down.png:/setupwizard/resources/bttn-ESC-up.png + :/setupwizard/resources/bttn-servo-standard-up.png + :/setupwizard/resources/bttn-servo-standard-dwn.png:/setupwizard/resources/bttn-servo-standard-up.png @@ -85,7 +85,7 @@ p, li { white-space: pre-wrap; } true - false + true true @@ -116,8 +116,8 @@ p, li { white-space: pre-wrap; } - :/setupwizard/resources/bttn-turbo-up.png - :/setupwizard/resources/bttn-turbo-down.png:/setupwizard/resources/bttn-turbo-up.png + :/setupwizard/resources/bttn-servo-digital-up.png + :/setupwizard/resources/bttn-servo-digital-dwn.png:/setupwizard/resources/bttn-servo-digital-up.png @@ -129,7 +129,7 @@ p, li { white-space: pre-wrap; } true - true + false true From 527ec1d15dd4a4017fbd076f840b36a4aba40690 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Fri, 22 Aug 2014 05:51:26 +1000 Subject: [PATCH 052/203] Add new artwork --- .../resources/bttn-servo-digital-dwn.png | Bin 0 -> 4200 bytes .../resources/bttn-servo-digital-up.png | Bin 0 -> 4903 bytes .../resources/bttn-servo-standard-dwn.png | Bin 0 -> 4270 bytes .../resources/bttn-servo-standard-up.png | Bin 0 -> 4934 bytes 4 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-servo-digital-dwn.png create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-servo-digital-up.png create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-servo-standard-dwn.png create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-servo-standard-up.png diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-servo-digital-dwn.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-servo-digital-dwn.png new file mode 100644 index 0000000000000000000000000000000000000000..90bac4ba1c85429ec749809fbfe5355aea1d3b83 GIT binary patch literal 4200 zcmbVPc|26@+aLQ{QP#pUMr16**tfCFVwsp2Q&A$z*fKMWiLoysLb7B@vL$Pw$Wkb> zmSp59vK5mhTe3y?jh5$qKkw)H{Qh{)=bZbT>ps_hU)Q<6C(aUMa)A3NHvj-QU}lQM zGVX5~mlr2HV?1nfn=t}JDJUC?HOZCY??}c2j9f@gc%T`<(G8EqJGun;bmR2^02Wsd zoDIds!d%ChM1VN%^FXKs?|pHAo&nX{(fJad0(8Q=c@SZsr6(;Qpoa?#bXMI$*}@xv zclR(2B;&0EF*xVIOU~LZAOn4%9#w~-fPkks0;vQqqOT4W2KuR2hw;2Wtpo!8WT9Mw zfqpq9YU&yqPz9ihGE_xLnQ>|;Le+HCHFQ)ofxizB z!y4JeRR@bS{%wmv!9ea5inorElE1${#9tLcBD*O;wY9bPb*QK)GB^}{1Betysv^-> z>W>B_-q)Gz;Z5-%5rO*}9i2#*DKHSj(_bMFye%yLQB3sxohU}il&Fs0N>GTh5`nNE z*H3O=3KsuAZu~2^FD}3vuY|?>k}i{-8SCLH^+%YIyZ>%zpON8>&MC47V^JKvkR<2J z1U!*qhJ=9_Zy+unE;=YUN>dq%G)AhSpeQI5YJ^Z$L7|LLMo>)+4K*n0kB)znRo7P4 z);3Z`sc37cL!l@&ZDpjkwy~zFvaykh5mE*IN7jt!OK~JRRkTrRjJT1;jHsb-O)XV~nzFho=(nuP|0ick3}=+~i{pP4%bzJm z1@1roQ~C_zpXR|68687rv_{zCLtX%YH`5Ghgrg46=WtPQgQA@+8?Gr_y7!=Q{ISw} zlHpxK@_EOxMz+ikYC9TN1uCwdi4Qy&_zW(1{rwrMpw+aZ_B$-n>W1Z3YH}w8)G8dU zqSVkp$9RQgX?B^ctasa^nxu!l<|{I((HVP(7PGn)mYSY6v}}ZIWN+IGSPXCi_#^~4 z*$j0L&kaAHeIGw@jlQ}2vc!ew(L!2;|KAm%4c22gxF{OZSZ}L1q z;i`A!UibN4Ysq2E3e{e>aVhoCEk)dtqrU>~^tK(UHhBz}pHlYn_}(KNACFDz@k-Me zoCHm8WaMFh-UF1$MzEfeOa2ybt{SQqHC3Xa3ohWQrj!bt))I+xVHe~+RI%bC@pu2o}M&8l%iFJ)MrN-y$PIdyaz2Sk~Q zWjzHol%X;z3*KkWpgu|Gb6qa&fprOe1ZKm~ob6aq_*cc3cb%44cv_Rq2BePg&<|U5 zP5FUwvy>v%AUDhW+k>}yC5GZ`r}?|&#_7MMQj-(4 z%OOK>A@scfv8*Wb+QKxsPAiQr)(ZKXpVPs)pJ6-jGZ+WmzC%N7vs(r+iw@>=w$8$JYf}HxI*^F1B+@v##6=2>hnT81xL=F)(2EvD*(f#zBi@JY=d^bH3H>F^0}o?PL>r21Jj1b4Me4V zqhv4k@=2>54zc^T9zf#1F8?8sH6^caj`p_f^Pmr>3e(Gu;#Y=QOvGV$*;|k zikxh%{BeA>=MFI<3%3Lq$^w7_fV|l}*?xA`2QQ+pWGOx-lmOr*>)^CFv|Z4!1`d$C z!UV|QX9jSx0iu`z@O=`%$IT$02_AAqZ|38R*`cbHGdnaX$*e#bUPF@zON)7}1*)fI z(0iqm?}Fjwn&Qt78uf6rk_8@rs5%0~4V0FZbzlH|a&}sh0^ycL zk2Nz!AZ|zOv*PaXvu00YQ|0qDo?HnW)#8WSCSPb+vZVA87o5)D30Z^boc(xL@Y@oJ z_JyYzl0QWHO!Lhu^q}3pl3lwvpX5K_u-g=$uBV-B%!^jr+3l3*x^W+zmixqXV7em0 z^30T_hiyFfT1S~h4e_K^PA4{Xa^|s>S#SCTx@gl~6suoOUiA`8^o(AsIOnaj)*y3k zY`iMKK+!(u6dOm<08i4pyZT|FuD43@s?V&d7>G4j7z8AHj{0{lSMBKUDasO4cQS82${O3vf6k<7dH;fZk%US!EF zA--57xnD#|bVOe-S)yBn9)GJ>x`#jFkUBs%yY6tvWYC)|o{ZU78-k&^nl9%wP9X02 zDKNDeY#$5r=@A)#p*2EbnuyH$Od=K%>b3KUqx9~)UQ_-2qh;}Es5LV@E5B@b(COu8 z(<#l64`=0gL|C>uUgmZt&XgaTOUi*ZT|aNKzR@k{d-^O|Kt(u5OW1o90CtG~M2QIl z_DYju26R;^3-iiN5X^USU6{NybF5|h6)8kOJ06Xh0ZYXgbR1Yfw1d>;VYZ9%THZRE zQndLZukv(v zRbYTW(b`1lYw1etmsXlwT-p&vpFM`F3FPbGoIKUxTPq^{i6_S+I_wE4t;Fq= z&=zubQTv4G+O19tiMn__$ccvXoGG&X;RTK@&$eUS9hM83Kbo%63Fka7#7#P{23(D3 ze&X4-7<1?Vyw-u&r=IHg?9t12)8ZxHMsYz*D6WM3VfEVSZ6DPM598E<;cb{24M`*U?^Mw{P{iOD+5_=+T9tYp!KvPWdO*Nxsp)Ez*OIPsB>Wzm3m zF|R6~qn|2etLv6!340Ht^oK)Zd*pAY`S>304V)1AKC;!fPIJ?ZpS2ufJ36-H8MrR& z@m79UZcA+s7_y0yT-aS#lWzAf79B9@pK&z1oW7l#xII(rUpH`Vy4Y&vvd?9SOLI?~ zhX-y_VTUkc=(;2ckyRLdIyA4BZJf6H74bDf3SO(P_hs9uC{^fHed3+wJ(<9;FOoew zpYnnqluRY0(R+vdY5bCdE0@pHCyRTOu*1vE*mV8s(b=SO{o<2~loW^0n*xC!lh2o! zoaJa*O;W^)u-H#mKV16qw0Xj?H0`nekKv9weiRq7#I?15a>!(jliXC_ms5SR*i_qa zudTwY`Q3#RpcmiKJCwLr;8OLaQwjM`m6EdTEBWv9(nvF>-9p%dd%3QoI$V!9n92ApFb*j$X-CUeUIb7@JUB#Sjy!3;w=eAy?Q=ngwLvu~~ieE5d z!$L$R+P3Lyc*30@V#PHleb;H99Fj7Q_}KPH?o@i*DCoglVbp}27>aAreY8=_eDKJ}`YT7pVIN2P=*hdUtFKH=-bVXO&a96(Xl@;^I2Gs_<}mH*S$vg* zC*&`orh;bUp1tFot|3h2>90=w@X`tXQDJA&pS(2FE&W$FbI*(ZckkkYBPLkFeU2R) z70h8m#id6?PaN!F@xvr(MIN^sy`bOG=ffYqMB3iU6f3VXza8nL)0LRC{wn;h&TM-n zVMEu^)N?21Hm~G{1u1K*vi*;Of+J)x^2L11fWsyZ}xQYwtZ&o$>Sr{D9p%r7}V3{Vdwi7$w9D`>KfvsRwM-1ILj?G8L zRJ;P;H~>KYgdhw!@e5@9LL|RH1_N`1f95JuuV*pjFj5^{yTUzaiy7F6#d~Zqt9P;K zWFp68#Q7jw6VoEXw zcQ=hl@?3rwm3?p?@=Bs$rCknbtp}kApr}2?yj)q{!+cfl;WQ=Mr-#WK z3U6yZgsIf6P7Q7BJr3moL$a4m`uGGb1}X!OM@OE1=BY8rN%xtx_=X!u*e0f8ScB?l zQ3gx(-UI8E)4Si=?o;wM1++&cuyp(jFK;dzE%>Z$R@*%+dfcYxHd!_Cq~o^E9W z94cC{gHdZ9^A?`>c@r_w!c&8&kuIRCtvj)Wg^PqQGyTM2|0hL&zxISL0vv>dU#`R> Rd-wnS%}^NR1Ng)~j7Ud82|*ALNJ2HCCLsu+7&=M~5PArZ06|el2-2h|y(vMZibxS@ zQl(3iB8mc1Bce!=CXP4EjC1dg@A-b*^PIEWTJLIm?X&keF*wr;K(3QqEG#TQLjyf? zW$0U3~}?kPE@X%TEiu+RzLJdAVtUZB$L5CjMxG zriJIDUbkCRa91Rg~DJUH8n+;imI9#Odg~Jg(*Rx%v((Xrh-saLnx_({<*+R zZGmp?2y;FCe{?Z>T3}BK#UBBIgoK1BhA1nN0zDuwI2?W;LrF=2$)P|F^`qda3VvkC z-xBl)WY<71e~K5$4|E_A??MWqXn~oQ{_O(M-^Ao!!G7d_0>um&go^ivz!aenBJsel zzqrX1bHe|c@gKR#mZAOxh&h2w3JP>(&WF3?Z!j}<|6S1mBhwnh#Xv9Sq~Lw^NUlLd zf*-|DPYcYXD7tyMAuuS6Iuxd-ucv~6VPG&A5)DQE#Kt*?qgK`|J(+Hb6(ADM#pb0z%N>&4Xj4_4{FViD*-0-iz& zv?P&ye`f&BlSCnrJxTr`w1pZ-#>UIfjTAzbJ(!-qz11TGdIb~Q^aDvm&|mRIc>M?c z>iX*F^UC^qs`^TBj0)3lJ$bsR(ZVEp^sEc&ZEXV1 z_0=x)$eQZSRF%ZsAF56n#?oGQ3m#FvUTjWwLu49iH~rdQeX-H6$H5}!iCUl+rz<)j zdOTIM%gu{#aVs1Jpd==~Y+a`37L}JfHT!>TBesD>6}N^oW229FZLPfhz|YU`WQ4_L z-MM?0HCH2q6N#(kU-rsxZ|~YmJ!b>b&=6hU*ig^W2=Uup9xENZ%9m!{NgqwP0F0GY zP#|{xafmIipx_p9!oBKF9-sq&Ewhd=EsPj`Z~+|_wtuwi{`EoND+&2O?WKg0cFd}% zYqN$Chk2%Gq9uhnbXeGlW|)DeM^@}RA2^S(KzfdJN?X%0gkPR!}uC)h$q)O%2QA@adTAZ<7xg> z=O8r9Ln*s|-kA29o8OqpG|KMXj@R@ybL(P%l*-Sq&1FjA?@VMEzt07riv3UJN#jJp zWzlhba&<|G%1;}HVM#t z{~#$5^!~MY`7x>Ie8}TXkzoS_Z$mRy17r4&=|%SUd|v!C>s*W$O)*OxV2M|Jx%=*& zXZTMIHC)%uiFMUNVTGV%rRbG=M?0fEmp<>67>&x7{h`J};QNwsCsA{0RxesYlM{UP zDEotN4C8x|LDHJrYATlLb+zL+bH&Zi*3{%hi@u4erEYct(g`~!G44Jq=qH$Pu;xt{ zuDIpll`9MveTSn#wsu^x187<8HEFla8DJJK@;LFt`W^HgG;h;3Z~^z`=GD{p7Oi8r zIUBQtWo#Qo)PwFAEhI(=wxFG^8ULcr=87eWUX0!r0*{H-=9#hjGWo z>K|%DA6XS}N+{%>ro3pmB;s1Ie`r|_(lXk^)3#cmWpeCPbY6;qj|p&=tx9Sn;)!tB zWphtAO_BBoo=MeuI4rs7TM>2W!pjlH@zz2quOR)Q<@gjEi(?C2!?s;FifN#51}?U2 z{UeE`;{IU%A+Uy`Zl<74$vQ{L*{&NjO<;lkGEJ9UlrWETJ*&kt_Ds5bx@$=GBqF4l z1J!eHzAHkXZBm)+JXh!x-eEa%dw5bpQ=WZ`Xg7@)i)ELZ-O{*#@(WNc8od{PsSJ4N znkO|1xLu$P1r+FLv${9_gwLniuQi{S*t}?)o{bb2Iuu;m(U9k>W?%|fh0aCwF7oYt zH=$LH5z2xS3^kn}iD};BStV+*rk9H5^lA4{SqFZaALD*=V`-%3r$e(9XX<4(gzMSy zEH+5?>g3tWhG^qU!XizYUnHnLrnXg|wQ6Q0Wt!hjgvPO-WA5`Ol>&zZ5!3hgo{8=J#cR#vAVk;bU^uOi54g7qhO8OU9 zz5dkv)}PgxpY6w;w%_TA3~4-(&9VOxPR@Pkmx~|gFNSK?6&lr^cnlr(dmdg)H?1I$ zd+Dq!7gxqFM>Ky>#+Ym$TjdpPWtS@OsXgRqC=To*$4$(1y;*&+e|&T-n}9~x-^!mI zgbS(yapxMNqH>bI8iuFeJH?Sau+KVqY=Ohoc3A#MpvOQ{b)&Aea?Ri^^W+HFh|Et?jU7NUNwt4;eJKRrXJd~)fHc3QvaAg#{ri(?^lcPpHn!RZNAe?2P6wfh9Z z5aZYXz~#XOsn3bK%k?#o5I;Spv!?wtZ*6!>(iDbQ6q?6#SeNFaw7GWoyXpQlq1V3E zsBc$HI#ay)&OsYDwj)lz5ltBdDq7ip4{dn%UAp$sMNNJ_A<$FM%}o==vH-u3TKKuM zh?W{#9QL#Bi<*UWlJCx(+Yy~(51Rb1e1Mm}rW@hDG`tryJ;Np@DpcPSUu z8nv~0>mZL;=o%l5<0BHpytiBJrRP5fR9k~5&T&RPr6k;vDoSGRNsEJ7s@%(;KexJ6 z$dp(tLMD$!rh2Q9%F1RGxAuNCIJle7P$bU`L7@{f@cPyd&z{ad>ggqmmkHh0mwbGw zigR)Be&PlBDPElqMjRq7M*~S|MJwl1qEN)ZCnoxGz>Rhc7IhjtH!lj>^wxPZ#*G+3jkA z;s8o33rZEqAlbP~Q}^;P@RV88mE{UMc@=~vRp7^c(-lrdnMd>y@5tzjO)8CH<02xk zho5X--;gb%4Q}lNGJ!|M5fd^9dk5U_rBjItoFdk zrN7D)?k;Y_9HXEp($}c-~4=VrO5d8?+@N= zzt4Wn7TZ@spFyQMUC9>}ssSBrh*+;FzM{4bL8zANxdy~mVOt#Z%dlllW5K}DKJE8i zX>)TEyw7!~cMAGcl@b@K77`UE*tKRQKgO7qZMYuNP$o}!Og{T1U>wQ_mKGryXF`wi zx$HNaVjm3!APE~nqh~a|uwkP*SDVCc0gXLRz6v)A_*RstM~iHU30E3FUVLtsi%W8@ z-U3WqEdF$3@EgeeHRbQmW6->3W4>$x3I0Yj+Z^K><`!}3O_@WhP z{O9*7akmep_xva)GV&N#WI`Q7azh+o6<+B*|4HpK+xc^T@Ttq!^IMrP-_*V24!;L- z;_wu4%n^r;58-U5GSADs?Z_QSO+hovu#gcMr`yqI{IdhhzHX1U+m{>Z ziTu!>c=)49t%&AcIP2dMZk~@;J<>})-4VxbmW!I{3wiz4Sx^04<7&0h9p_iX7j#_! zubJk)7Q@AyH*o9p09h8B#~p}cz86K?#D*;xREFN6NuIA){hO&|NKTh<71hs&W=M$3p7DPTo^bw{BUMn@~sDcDn-Ti>AKINuZFcTUgDIH)On1Q zAatXr;p3FXUMu;=)RFAqQ;}y^#e2uQ)^)6bAB?u-I;Jez-f$IlaUWfJmB|(#AMb22 zLHQ~8xu(6j5)v^mbA8gClASUITVW`i8e*7>AY$6pzItbL%?qS)*njeomBH5iBzp+n z5UwK(xB?R*>&+*s{BF*^%(pH@7LK%*Sd}tZ(Ki6YR|n|+x>yd$U`{wy_Q#dkL65CX zt(++5$SIrf#dQw*l%YfY2}J2960Ci6&l)%~^x5ikrdaQE32nCDkVBf^L`*sg94_?r zqn1=Ry_+63NUugLvy)C^4o|d*VT-Mr-hSf8Pf>vJ#~>NTy&9j4$h)lUq?O|8?5ljl z6!h*%4d&tY;Fy*Nn7swum3c1-n0}^v40D{gfTNhFgZ4+*m{fLNJ^^I4Rrit)SpPWo z$nNEN9QBzZ^StZRR+^{i)MTt>aQwPwn@@Lob~blFK!Cs&FU^3z36bKk*H~LCQdw11 zEPMpT^6ZbSZx4kl&~LQ>+?AD;8U0dc&!Q<5l^1bCrzRzGVph#Q~RrGR}ypasl$pwFU3XMKK zBAl6-=@T0lS01hB7F3%WuaPn!AqT9TntT7rQrTlb?0!-b^sO^A@9ELeep+~70q0GN z@MvwPhTt!LCp=uXRhDLF!_DK^JF*?Y@@0BqCu1J)z66pCz|SjUPYTD|8n|~U#Tnq# zQqeNrF-BfzOglOreg{b_%J2yVJm5N_*TGR-B+qB28oMDKz$m;Mjh39Vd|kj>RtiS) zp2FdR&HUU_&)>mxX6A&ZU<+jEcLL6pxz%B%-%G-HPhl(vz!7IQtGa9N+L@sg_@c4; zmfo35a$MU04%#*I!ph!x8@07Pdl8VNe8nH5Gmh3aJ+v_PfCq8C#Jdp>V=#nt0M=SW z&R+-eC@nyWkDq?VtS81OxPW%vZR3pm8u=SYnonq$7o}ZXqzgWseR#Mc=oh4gMMHnZ VZ{8@+>)_XwA;whi3CcPAe*nd7sTcqN literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-servo-standard-dwn.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-servo-standard-dwn.png new file mode 100644 index 0000000000000000000000000000000000000000..dfbf34c45f69b2614211ea2f0a0684839174f622 GIT binary patch literal 4270 zcmbVQc{r5o-=Az}ER`^dCdN3j4`UgOeat8_V=Nh|2s0SV%$S)PWGkF3S+cd*GIlMJ z5`}S2AzRKMMM$!jy>cYH<5cJOUhj3T-yiRDJ^#F1Ry2#{f7T$xT(A12F_P6AjGsa_NCm@K#^n`>21yUHu5L4*ia*@2}ooOv7 zb>D9D+c=;ClK91Y856qYc;5(&n8AO}HLXAA!^{ zfc!Y1JZ*HM57H5B{X-XzGKKmvnKY!97K_D#v2(u6D>})O zNu@hesewN;0Pja-QW<_!8pO&80Z}24DMTuZp}G^E@2f?V=;U)GqBWfw1o_*)Nbs#v>VR+VCqOEzWhNBD&b*=QY^>v{?c!~cXpK0-o(b`Fl|CKC1r+68- z^Y~Bd^N4?nheY9344qdR9b$H60D#!24cgKH&=$c7jT@7?iW4=PX-AH6U4TBq^~b)y5+CUsnNxSuA6>0tO3z8H!V~EFoib%1JdDv($cAOHJ4(+_qzmINbiOGW5|+u$4eP@| zyFHc50`(>LWJ^n<^?sZCvuX3&TtQE|f8u`c62o+_3XN)I9LOgLavo8e1w*Zv{=p~_H>n1O< zw)8DjaPyZP>+M#DFU}q}19*WjPO;W2EG6z5=Ib=w(xpxjWSiZ39HV8SlFu=hQDVfZ zi03HS`u+N~Zfb7zE)-0tjS)zXemmD2;=I}bzGw&WdG9ozbZeF%Ahg1 zj{@*30NB7-K1kxVVBig*tQ?n(@NBa)e0#)V`SuAv99(nB_gv%r#?N19QFrC2FOn@C z%g2pJ$Gh#{Bc%k0#shfi1d#$jnE1>(V82H~l2G5lptty4vG}W{cu(hXSV@GHpt!0$ zKwJa>6#NeZj|3F%kf*+k*$SKMEtFVxed_#L_W;*kj8Hu>qav>MEQKNLAVX*0^8cC!^hy4=y(8x$4tF;Mpo;?E zw@e1iY-*|dt!Fr?-0@~_tiByKvaH3IZ!JqjL5s|NYay>43g90;o_K9Q6(acw4MJc#a*40j!gIP_90&+Xy8zf9$XvkjRd zK#)-egE8?JxwS^VgWNNd*uxRr`3cmm$y}UJSXi%P*>e3!mydXxwZX@w8cN{py|0fz6fAUmO}oRzq+H?}g_(B$Is9QgfHC zv(_7oXTRiZv`37qbm~;!v%V7Nv2JP+>#yw+kn91kt3JA}WIPPwJoc`5JbR|SRU~XS z2J2qHI!2k-rLOucf4 z6hfD`#tFJ<9xHzc=BM6(k6n62Yh@0zTxlkQ2kw87rXcEQq)-R$dK#pQ<`Ghgqfh{}U4H_wyUtp2Ars%p6& zquDu{nlmzkTUma;qJ0 zUSq!1y*2Z>jZ)GDJ2bbcAs!V`pJrQoD7`Pi%lMJli<=vZb+F>ie8c-Jt4@g-Ks=sH zvVR%eag>5d9frHsa;>V;3u^2%hUV)B`)dM>Z)~P|4L!b9>F}k{W9{67F_z-&WA{8i z%<`Usc`!1pce-)fra5Cyz9-fp^WIH<2rAAg6X>30c(&D+Jb!XMcmB~wq=s?WXr1NC z=G^Y{72!Rse&t(?XWZ0x2ZcWLKCZ`Db8g>lryF~OA6IzvzTV_WmHEioyoS7q-={yR z_pB$LRb;O;+!|OYZafl|U4VTO1Uzd?Iat@n+vooBp zI-mR?#06TSq})4PQo!xq%PAztdi)q-vJ`_SuIXL$E zb%Wu>6_cphd@rLs1D#9OySvXtvBqfn5%`9@NMukJ_fnLxPA%y&*VWnwJ8LF$!agz7 ze6Vgm%CcNE)mMa->Ib%|oV$GD+WiRg=g-Gdhb>JT5+%Tu*_K@N}-SDU>(?R+5>mR2Q<^yaf*^<=QkO>4ZU`h(~go>Dz>~Rq05&#BrK;x);Ft2ZKS%P zHvTA|mE?#CbDb#rNO8697jee<&KkM}S8OF4IZbTMU=os77>cNB ziw65sp?ZlDjD@EBQJ5No>ib99<(m>Y-7|>KU%q@G@LMNp&hLl?;bA3d)tqMqz|= zOpDiv%h7KA8zU{nW^h+p)D>8!e8#TUo#uo_j$sSLiZF-?8wU8yXgt?gMfgszxCK%9 zAehf%RO7YAL0&oi=wbkUI*MvxEc5IGr!2oQ|_gUQXhIh zf&9}%_23Dout>-$;JFXB%}L%hx=5p17ciWRQ^=b7lPW5WV_2CBVO3W<)&`PF4d;th6PGfnGQFtKY+=AvQgm;Ds^`_@ji&IX z*lRw@e43R4>#t^7IiIRh3ER5c$8=hh(%QlHmDlBay$0lap>Y?FLk0pXK^^2r8BZya zRnxPhHm~}uoZ4{Wx*)Wg)N22YKTTb8 c_qN~x0Go!OQ4LG_cK#sPU~uTWs52M;2i`_?=Kufz literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-servo-standard-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-servo-standard-up.png new file mode 100644 index 0000000000000000000000000000000000000000..bd2d067a7b303cdcbce1986418b1e61d9f4f9342 GIT binary patch literal 4934 zcmbVQXH-+$wvI@X4pJ0CmEMz(&}#zHr9?plq=ilrNT`A$9h4$XdLSquy-F95ARtN+ z1*M1}2uSFtfQm1kb3E_;xa0nKd+fdTD)akhS#yrP#!j>_zsStM%K!iXn2ih(R+RT^ z%HvB`l_J|01xoL{nK+P1*uyB;8 zmtj}{$~w#(=^Ezas_G`9ttF%pqDCR`L*bo;Li~KuIJFQ>k-vD=DE;5l3L-*(iQs)S zMgBI**33c(jtM{sLFFNGu8JU#5DX>{Qi8%@AXy=>A_%OYNV#EhASE>@Obx6o^v@+i z(H7w5u4aWW_(vCIq$%Qw$79tL6oP|;<%1#em;et2kgBTcZw@e6jv^t43q|9dL*&r7 z3x608D4c767Z&e@K@0t6bauf6;x$Dmmj3O6AJ)w5Ut%=wpFmMUrV!$cRRGB=D){;R z_UkWc9Nr4`zh?YLX&f>Xi&C&c;V^*#u9W?7zwif4iQRu!^jnZ(joPIEFUqDk`yw!| zfqp17-Uy*7LRpb_^Kw(u*V9*41R)F%O8Ovu5D26TR|M

+0)*lwmL>kp3Tz|AaNr zRfOy5K|x?uCC``57r2c!#ks0QGfJ$QS|3S-0T@4_zv8Rr z^&j*@L2$4NSP2A$f>rgED1IXhC|-l~lvN;bB}FJiT*!#!yv!XpcAx<^iewYIy+bdX zIwXS-W~`E-PjJyaBl3j7n}+j&q;1yTCe@wd+S(3VX)AhZyN9(M(iIhwE-{U^wvJK) zBBx>`sSP6mM&gj+7ruo2^|H=MNN%pE#;ac!=ks!l)aMI7o%|%=j?Gh(6MT`;a;6zY zH;>nM6B83BePOeJcCoVnZsBuG*&}{cgCDQLJVpyHE$g3h1eV2e-D7+8A{U|_wEk+P zp}M;I5v7b?H=<0^X$JWE?$MeFpsMd@XTM6}SFb28b~-A7#}{4i3fbLWj9F3imy|m2 z^Z+rR2fKNX6=^=It~RY!VWZcv=mkfmizXJBOEB}n?t;PKvbgtQ7NGjH`pi{WO=NTG zR~km{yW7)s3+i3O$?{7XzM;$Cz6*;xsamQ6SpqueGxPF{LqkI|2?TAg_g$gDlOw1( z*SK2dR3UjTJw3h5F?1yh>F8+gSZAY>(Rd0_P0e@4C$gpYQ7Z7b!Mf%({*2_kA~%k$ zGnT_wg1J^rwFs=E)YXnTY`ji#_2RaC!XNJ`-793v>^C+2A*pT&NfCUP%Nb17TPdmL zWL6JTvYX%*^K};{ys``wiwOl31Xr;o<%pUMc|hXAXEYc9YyzFabJjS?Qgx%eIR=1J zilqWfY}p!^^a7aFuNe~#cx@bEd*Nnu5Z>IaKv)^YE_S>#dbFD*UK zO+sbvf9xfl+k5knhmIu!YPk6}p2Pap>**rMfQn>tQ8BZtsCvKDWcYiV?EW9xI$ zuLV~&33l2NA^db?JqCv95?MmX>9d*$Du@W6ElpSu$iPBF)P@a}$WujQima+Qrr9Ll zbcHM~4VY!Du1nuyus=1oGcbEN77cd@%elP7OV#Ag!08}X5z7jzFW4N=tU?hBiyM{8-VR_TW z#H-q1Sw;)`QYe6L_;B^y^ri49X>%USuUxs!aWYvI&s@AVbutUC^_9~7BB+s+Wc++cJXYC#_?}Mf1Md6bZNczg zqe{WYhIVau=7`o!Y;@hPx{m?tU-OSA)7CL-ch2tZ8lm6ZwjY+_Jg}K&SEZ|P$SFB;EByEFj}Cz1`xjR5~Z`EvHc5d7kljx|hckF=`Ahqgt4oNRRs7iLgFZ7T~)uXUG^IVh?mWymvNKpJ`RP zYpJR0E+6aCcL}Dch@$EI_m%B49zV0GEZK&<7p$1&u1aDeIxM@iF}u@Bik&7k5wdkV zk7fzSuP^G6tT9`48;~&1>sNcv5Lxde9?dRqNH#^tu#fKTwea1VNSsxyHf(f$+gswo znW<2raL}OhRY1PX$o0ffK}+e1%F9)4@&hiPAOrjRyFbm2;$v*@YP2t3`*PG-)q3Yt zgjtZpOmK51?Fzo6rjxa5!zK8m-vVyqO-G<7f3mhs$N^{I=39g5_`o!i zzhmc`Uf#ry`JUB9QpfADaKV>0S%=;`e19sh&aNDka=w+B<8();RTNr?&pFsx*Ui0| zfiOF~gnSBy95%@!KaZ#=Q%y?@Y3R;$LDyjNz~ z6={gLWtKDDgv+a)6TGSIN1{zhW7SW5o5Ycqkh;$l1bApz+{U^pU@Tc?pUOL46+Kg4 zO*Ft7vqx)});!f`#6-6a5IjP(pE)dCBJf>4t}uz8a=Femn8fK`xmX7DZp`o(vwC-_ z)~<0jcVxJ%vjDI(R8k!T3s4o^LvG+C1*%7W-Hb;Ad`xBw#&LluH2ukho*#<_pJz+E zC0!)V`w1W!V?!pSv8?`nvW`Xv2OKZLCl7Y+b>X*G+9#Ud~jEW)!i9 zO>armX}`KD;(dmXJwsho)}z8-_Flc`1TpG7#64~BBfCv!4e9!)+Tx}s)F2G=+U|Gh zM-JXlxrjaVMtf?%F6E2g>^97ir+EW*U#Gj|3YYhrLoH<6BoqA&Uul`D-3ZBLi{cV` zYAn;zXi4>&h5Y^QXG6E&MW$Wq=co+FR;(Fe4K=)&>8N^3ctv-)LCO53r9~b-GAA!3 zjdM6iW~on;&m0k28yWP^#Do`@=vWd3gb7@m^P5i#783--oYm~QsZr2^AfuE+VrNeG z&Gm?m>HX`!@}^dP8O%eh))J-Qk1no0ZuTEMW%oFMaZ^F9bmRMYVKnKZi6AuxZui{q`O zD>ElJ;h!HjHNrmBYBT!JeY(V7udiuk}AA?vf>* z@B>?m_44#AsaUwWi=#L%TSkq2b!S>DGT)+>(0sgnV>fJo=bGolg;r9R;NsjEy*h`2 zVCYK_Z%&~UHPj!0$-DWzW$CB2$8)bmz6DEk9gEV^XGfRw>U?$ErtSB|7Ya;NHPspX zpR|TuD|FdEu2eK!V&}Yxl>-CSKr+8n?`eb+;(u+H|61NG$y}zcJSY;xU;9R|h%M8w zIj2#q{$*>*JYv2B1(~T2>=`{$Y5sWgi0;zsnRwCGJ8`Rc;@##?_{(*scKee84dIhp z7n;9~8#i>@c%%~5(L>x+9(|jtSW{-Hqwb~2RqrQu+M$Zcd_@lN#lDC9BGH<#>KcbbS0Mh6^WI;BC4?ciQr$ z#?tL7CgYngHZzR!gSi$jkN9b64X@kQi-T9=ITD&N$`d=8_WW!nlGenvSz&<$xIaeB?Vk6gtYEXHcm zTx;ID(;n`>g#RF+yTQqopb+0kgeS7`gy}i*4=ympQ-Sg_lBu{my;y+^O5SZe%{!)N zRFJ?nV2%#QL@72Zd90+`Zso?O38`~RfgiruZOg-QMtCGBM{c@PO6DwFeq?&ep^XMW zP1B3w+Y_EUEfgl#TLNgaV2Qoc0U(vpsc-_A=_#wR3`ayW5}@9A$VMT439~^3AWkC? zx>=c-ALyyrqQynx!aIXDi9wq)!sOFBrHP*W(w^atwzh`qLF8UbYMr>2-aPtpo*Fn! zKmDD@ezW4fwU-E5nc3OmH|+!fRlTjIGV=0e^PRyy1DscoEE%!H;hnPytLFjP zh$(~ED>5^!q7ab({!w@*)!`#G0KQ(_&5x|~SwA06V`leZZK8C0pJ&q|4Ny!wMdcIK z(#H#$WT_h9V)%LJjvpQOL7&-Q9lM@WRCKd^Waa4ub$0v!euDd1VO(GNRW#ueKOioVsQxncnx1Oj~Y6 zTBg4su5ZD{-DV$)$XklCM82W5yzI3v?ziRvN$5u}A)mQVAGGLN6rW*`t{6`KK`T)S z^B0GvHs*4Qk;Ty~in6V_F*n%GdP)iRq?AvusS|GG zh=1;A=6Ia%V$8z`b7vB@^X)RWz4Q9|w7b+#6U+~O_5e-;oYEP>XDn>ofB)Gs(lN!RI4;f#!ssI20 literal 0 HcmV?d00001 From a7ab68f53961b9b20eb6cba3eb7a9bd81b8b6201 Mon Sep 17 00:00:00 2001 From: m_thread Date: Thu, 21 Aug 2014 23:47:18 +0200 Subject: [PATCH 053/203] OP-1222 Fixed a 'off-by-one' bug with channels. Fixed some bugs in the configuration plugin regarding fixed wings. --- .../configfixedwingwidget.cpp | 20 ++++-- .../cfg_vehicletypes/configfixedwingwidget.h | 1 + .../pages/outputcalibrationpage.cpp | 4 +- .../vehicleconfigurationhelper.cpp | 66 +++++++++---------- 4 files changed, 50 insertions(+), 41 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 47b8d050a..25306c0af 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -107,6 +107,18 @@ QStringList ConfigFixedWingWidget::getChannelDescriptions() return channelDesc; } +void ConfigFixedWingWidget::resetChannelboxesAndSliders() +{ + m_aircraft->fwRudder1ChannelBox->setEnabled(false); + m_aircraft->fwRudder2ChannelBox->setEnabled(false); + m_aircraft->fwElevator1ChannelBox->setEnabled(false); + m_aircraft->fwElevator2ChannelBox->setEnabled(false); + m_aircraft->fwAileron1ChannelBox->setEnabled(false); + m_aircraft->fwAileron2ChannelBox->setEnabled(false); + m_aircraft->elevonSlider1->setEnabled(false); + m_aircraft->elevonSlider2->setEnabled(false); +} + void ConfigFixedWingWidget::setupUI(QString frameType) { Q_ASSERT(m_aircraft); @@ -126,6 +138,8 @@ void ConfigFixedWingWidget::setupUI(QString frameType) if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") { plane->setElementId("aileron"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevator aileron rudder")); + resetChannelboxesAndSliders(); + m_aircraft->fwRudder1ChannelBox->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true); m_aircraft->fwElevator1ChannelBox->setEnabled(true); @@ -138,15 +152,12 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); - m_aircraft->elevonSlider1->setEnabled(false); - m_aircraft->elevonSlider2->setEnabled(false); } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { // do nothing for now } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { plane->setElementId("elevon"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); - m_aircraft->fwRudder1ChannelBox->setEnabled(false); - m_aircraft->fwRudder2ChannelBox->setEnabled(false); + resetChannelboxesAndSliders(); m_aircraft->fwElevator1Label->setText("Elevon 1"); m_aircraft->fwElevator1ChannelBox->setEnabled(true); @@ -156,6 +167,7 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwAileron1Label->setText("Aileron 1"); m_aircraft->fwAileron2Label->setText("Aileron 2"); + m_aircraft->elevonLabel1->setText("Roll"); m_aircraft->elevonLabel2->setText("Pitch"); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index 67048fa53..295be3b4c 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -53,6 +53,7 @@ public: virtual void refreshWidgetsValues(QString frameType); virtual QString updateConfigObjectsFromWidgets(); + void resetChannelboxesAndSliders(); protected: void showEvent(QShowEvent *event); void resizeEvent(QResizeEvent *event); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 4d9c74930..62239be4d 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -177,7 +177,7 @@ void OutputCalibrationPage::setupVehicle() m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4; m_vehicleElementIds << "aileron" << "aileron-frame" << "aileron-motor" << "aileron-ail-left" << "aileron-ail-right" << "aileron-rudder" << "aileron-elevator"; m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3 << 4 << 4 << 4 << 5 << 5 << 5; - m_channelIndex << 0 << 3 << 0 << 0 << 0 << 1 << 1 << 1 << 2 << 2 << 2 << 4 << 4 << 4; + m_channelIndex << 0 << 2 << 0 << 0 << 0 << 1 << 1 << 1 << 3 << 3 << 3 << 4 << 4 << 4; setupActuatorMinMaxAndNeutral(3, 3, 5); @@ -188,7 +188,7 @@ void OutputCalibrationPage::setupVehicle() m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4; m_vehicleElementIds << "elevon" << "elevon-frame" << "elevon-motor" << "elevon-left" << "elevon-right"; m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3; - m_channelIndex << 0 << 3 << 0 << 0 << 0 << 1 << 1 << 1; + m_channelIndex << 0 << 2 << 0 << 0 << 0 << 1 << 1 << 1; setupActuatorMinMaxAndNeutral(3, 3, 3); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 6aa002df7..185d0b1fb 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -363,11 +363,7 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() actSettings->setData(data); addModifiedObject(actSettings, tr("Writing actuator settings")); - // Set up model view image here? - // loop through all the window instances and check which are of the type ModelViewGadget. - // per m_thread on each instance setAcFileName(QString model_file_name) and then call reloadScene() on the same object. - - break; + break; } case VehicleConfigurationSource::VEHICLE_HELI: @@ -1548,30 +1544,30 @@ void VehicleConfigurationHelper::setupElevon() mixerChannelSettings channels[10]; GUIConfigDataUnion guiSettings = getGUIConfigData(); - channels[0].type = MIXER_TYPE_MOTOR; - channels[0].throttle1 = 100; + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = 0; + channels[2].pitch = 0; + channels[2].yaw = 0; + + channels[0].type = MIXER_TYPE_SERVO; + channels[0].throttle1 = 0; channels[0].throttle2 = 0; - channels[0].roll = 0; - channels[0].pitch = 0; + channels[0].roll = -100; + channels[0].pitch = 100; channels[0].yaw = 0; channels[1].type = MIXER_TYPE_SERVO; channels[1].throttle1 = 0; channels[1].throttle2 = 0; - channels[1].roll = -100; - channels[1].pitch = 100; + channels[1].roll = 100; + channels[1].pitch = -100; channels[1].yaw = 0; - channels[2].type = MIXER_TYPE_SERVO; - channels[2].throttle1 = 0; - channels[2].throttle2 = 0; - channels[2].roll = 100; - channels[2].pitch = -100; - channels[2].yaw = 0; - - guiSettings.fixedwing.FixedWingThrottle = 1; - guiSettings.fixedwing.FixedWingRoll1 = 2; - guiSettings.fixedwing.FixedWingRoll2 = 3; + guiSettings.fixedwing.FixedWingThrottle = 3; + guiSettings.fixedwing.FixedWingPitch1 = 1; + guiSettings.fixedwing.FixedWingPitch2 = 2; applyMixerConfiguration(channels); applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON, guiSettings); @@ -1587,27 +1583,27 @@ void VehicleConfigurationHelper::setupAileron() mixerChannelSettings channels[10]; GUIConfigDataUnion guiSettings = getGUIConfigData(); - channels[0].type = MIXER_TYPE_MOTOR; - channels[0].throttle1 = 100; + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = 0; + channels[2].pitch = 0; + channels[2].yaw = 0; + + channels[0].type = MIXER_TYPE_SERVO; + channels[0].throttle1 = 0; channels[0].throttle2 = 0; - channels[0].roll = 0; + channels[0].roll = -100; channels[0].pitch = 0; channels[0].yaw = 0; channels[1].type = MIXER_TYPE_SERVO; channels[1].throttle1 = 0; channels[1].throttle2 = 0; - channels[1].roll = -100; + channels[1].roll = 100; channels[1].pitch = 0; channels[1].yaw = 0; - channels[2].type = MIXER_TYPE_SERVO; - channels[2].throttle1 = 0; - channels[2].throttle2 = 0; - channels[2].roll = 100; - channels[2].pitch = 0; - channels[2].yaw = 0; - channels[3].type = MIXER_TYPE_SERVO; channels[3].throttle1 = 0; channels[3].throttle2 = 0; @@ -1622,9 +1618,9 @@ void VehicleConfigurationHelper::setupAileron() channels[4].pitch = 0; channels[4].yaw = 100; - guiSettings.fixedwing.FixedWingThrottle = 1; - guiSettings.fixedwing.FixedWingRoll1 = 2; - guiSettings.fixedwing.FixedWingRoll2 = 3; + guiSettings.fixedwing.FixedWingThrottle = 3; + guiSettings.fixedwing.FixedWingRoll1 = 1; + guiSettings.fixedwing.FixedWingRoll2 = 2; guiSettings.fixedwing.FixedWingPitch1 = 4; guiSettings.fixedwing.FixedWingYaw1 = 5; From a893f6ff2bfd00b8573b6ae6a26244499fd05320 Mon Sep 17 00:00:00 2001 From: m_thread Date: Fri, 22 Aug 2014 01:40:05 +0200 Subject: [PATCH 054/203] OP-1222 Renamed some pages. Added support for both esc and servo types. --- .../pages/{outputpage.cpp => escpage.cpp} | 22 ++--- .../pages/{outputpage.h => escpage.h} | 22 ++--- .../pages/{outputpage.ui => escpage.ui} | 4 +- .../pages/outputcalibrationpage.cpp | 2 +- ...{outputfixedwingpage.cpp => servopage.cpp} | 16 ++-- .../{outputfixedwingpage.h => servopage.h} | 10 +-- .../{outputfixedwingpage.ui => servopage.ui} | 4 +- .../src/plugins/setupwizard/setupwizard.cpp | 51 +++++++----- .../src/plugins/setupwizard/setupwizard.h | 20 +++-- .../src/plugins/setupwizard/setupwizard.pro | 18 ++-- .../vehicleconfigurationhelper.cpp | 83 ++++++++++--------- .../setupwizard/vehicleconfigurationsource.h | 6 +- 12 files changed, 146 insertions(+), 112 deletions(-) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{outputpage.cpp => escpage.cpp} (74%) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{outputpage.h => escpage.h} (77%) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{outputpage.ui => escpage.ui} (98%) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{outputfixedwingpage.cpp => servopage.cpp} (75%) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{outputfixedwingpage.h => servopage.h} (85%) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{outputfixedwingpage.ui => servopage.ui} (98%) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.cpp similarity index 74% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.cpp rename to ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.cpp index b00c6cfa3..75d8d6c77 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.cpp @@ -1,11 +1,11 @@ /** ****************************************************************************** * - * @file outputpage.cpp - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @file escpage.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. * @addtogroup * @{ - * @addtogroup OutputPage + * @addtogroup EscPage * @{ * @brief *****************************************************************************/ @@ -25,29 +25,29 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "outputpage.h" -#include "ui_outputpage.h" +#include "escpage.h" +#include "ui_escpage.h" #include "setupwizard.h" -OutputPage::OutputPage(SetupWizard *wizard, QWidget *parent) : +EscPage::EscPage(SetupWizard *wizard, QWidget *parent) : AbstractWizardPage(wizard, parent), - ui(new Ui::OutputPage) + ui(new Ui::EscPage) { ui->setupUi(this); } -OutputPage::~OutputPage() +EscPage::~EscPage() { delete ui; } -bool OutputPage::validatePage() +bool EscPage::validatePage() { if (ui->rapidESCButton->isChecked()) { - getWizard()->setActuatorType(SetupWizard::ESC_RAPID); + getWizard()->setEscType(SetupWizard::ESC_RAPID); } else { - getWizard()->setActuatorType(SetupWizard::ESC_LEGACY); + getWizard()->setEscType(SetupWizard::ESC_LEGACY); } return true; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.h similarity index 77% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.h rename to ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.h index 40ba78ac3..001122e46 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.h @@ -1,11 +1,11 @@ /** ****************************************************************************** * - * @file outputpage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @file escpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. * @addtogroup * @{ - * @addtogroup OutputPage + * @addtogroup EscPage * @{ * @brief *****************************************************************************/ @@ -25,25 +25,25 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef OUTPUTPAGE_H -#define OUTPUTPAGE_H +#ifndef ESCPAGE_H +#define ESCPAGE_H #include "abstractwizardpage.h" namespace Ui { -class OutputPage; +class EscPage; } -class OutputPage : public AbstractWizardPage { +class EscPage : public AbstractWizardPage { Q_OBJECT public: - explicit OutputPage(SetupWizard *wizard, QWidget *parent = 0); - ~OutputPage(); + explicit EscPage(SetupWizard *wizard, QWidget *parent = 0); + ~EscPage(); bool validatePage(); private: - Ui::OutputPage *ui; + Ui::EscPage *ui; }; -#endif // OUTPUTPAGE_H +#endif // ESCPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui similarity index 98% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui rename to ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui index e7f65cc6f..c06ca1d7d 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui @@ -1,7 +1,7 @@ - OutputPage - + EscPage + 0 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 62239be4d..4affe5c19 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -120,7 +120,7 @@ void OutputCalibrationPage::setupVehicle() // The channel number to configure for each step. m_channelIndex << 0 << 0 << 1 << 2 << 3 << 3 << 3; - setupActuatorMinMaxAndNeutral(0, 1, 3); + setupActuatorMinMaxAndNeutral(0, 2, 3); getWizard()->setActuatorSettings(m_actuatorSettings); break; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/servopage.cpp similarity index 75% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.cpp rename to ground/openpilotgcs/src/plugins/setupwizard/pages/servopage.cpp index 2977e9606..c95170a68 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/servopage.cpp @@ -25,28 +25,28 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "outputfixedwingpage.h" -#include "ui_outputfixedwingpage.h" +#include "servopage.h" +#include "ui_servopage.h" #include "setupwizard.h" -OutputFixedwingPage::OutputFixedwingPage(SetupWizard *wizard, QWidget *parent) : +ServoPage::ServoPage(SetupWizard *wizard, QWidget *parent) : AbstractWizardPage(wizard, parent), - ui(new Ui::OutputFixedwingPage) + ui(new Ui::ServoPage) { ui->setupUi(this); } -OutputFixedwingPage::~OutputFixedwingPage() +ServoPage::~ServoPage() { delete ui; } -bool OutputFixedwingPage::validatePage() +bool ServoPage::validatePage() { if (ui->ServoTypeButton->isChecked()) { - getWizard()->setActuatorType(SetupWizard::SERVO_DIGITAL); + getWizard()->setServoType(SetupWizard::SERVO_DIGITAL); } else { - getWizard()->setActuatorType(SetupWizard::SERVO_ANALOG); + getWizard()->setServoType(SetupWizard::SERVO_ANALOG); } return true; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/servopage.h similarity index 85% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.h rename to ground/openpilotgcs/src/plugins/setupwizard/pages/servopage.h index b68dd4fbc..47057bd96 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/servopage.h @@ -31,19 +31,19 @@ #include "abstractwizardpage.h" namespace Ui { -class OutputFixedwingPage; +class ServoPage; } -class OutputFixedwingPage : public AbstractWizardPage { +class ServoPage : public AbstractWizardPage { Q_OBJECT public: - explicit OutputFixedwingPage(SetupWizard *wizard, QWidget *parent = 0); - ~OutputFixedwingPage(); + explicit ServoPage(SetupWizard *wizard, QWidget *parent = 0); + ~ServoPage(); bool validatePage(); private: - Ui::OutputFixedwingPage *ui; + Ui::ServoPage *ui; }; #endif // OUTPUTFIXEDWINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/servopage.ui similarity index 98% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.ui rename to ground/openpilotgcs/src/plugins/setupwizard/pages/servopage.ui index bfc0258a2..e7ff09537 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputfixedwingpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/servopage.ui @@ -1,7 +1,7 @@ - OutputFixedwingPage - + ServoPage + 0 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 65e12f2ff..02e1ef260 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -35,8 +35,8 @@ #include "pages/helipage.h" #include "pages/surfacepage.h" #include "pages/inputpage.h" -#include "pages/outputpage.h" -#include "pages/outputfixedwingpage.h" +#include "pages/escpage.h" +#include "pages/servopage.h" #include "pages/biascalibrationpage.h" #include "pages/summarypage.h" #include "pages/savepage.h" @@ -54,7 +54,8 @@ SetupWizard::SetupWizard(QWidget *parent) : QWizard(parent), VehicleConfigurationSource(), m_controllerType(CONTROLLER_UNKNOWN), m_vehicleType(VEHICLE_UNKNOWN), m_inputType(INPUT_UNKNOWN), m_escType(ESC_UNKNOWN), - m_calibrationPerformed(false), m_restartNeeded(false), m_connectionManager(0) + m_servoType(SERVO_UNKNOWN), m_calibrationPerformed(false), m_restartNeeded(false), + m_connectionManager(0) { setWindowTitle(tr("OpenPilot Setup Wizard")); setOption(QWizard::IndependentPages, false); @@ -112,10 +113,10 @@ int SetupWizard::nextId() const } } case PAGE_MULTI: - return PAGE_OUTPUT; + return PAGE_ESC; case PAGE_FIXEDWING: - return PAGE_OUTPUT_FIXEDWING; + return PAGE_SERVO; case PAGE_INPUT: if (isRestartNeeded()) { @@ -127,10 +128,14 @@ int SetupWizard::nextId() const case PAGE_REBOOT: return PAGE_VEHICLES; - case PAGE_OUTPUT: - return PAGE_SUMMARY; + case PAGE_ESC: + if (getVehicleSubType() == MULTI_ROTOR_TRI_Y) { + return PAGE_SERVO; + } else { + return PAGE_SUMMARY; + } - case PAGE_OUTPUT_FIXEDWING: + case PAGE_SERVO: return PAGE_SUMMARY; case PAGE_BIAS_CALIBRATION: @@ -306,25 +311,33 @@ QString SetupWizard::getSummaryText() } summary.append("
"); - summary.append("").append(tr("Actuator type: ")).append(""); - switch (getActuatorType()) { + summary.append("").append(tr("Speed Controller (ESC) type: ")).append(""); + switch (getEscType()) { case ESC_LEGACY: summary.append(tr("Legacy ESC (50 Hz)")); break; case ESC_RAPID: summary.append(tr("Rapid ESC (400 Hz)")); break; - case SERVO_ANALOG: - summary.append(tr("Analog Servos (50 Hz)")); - break; - case SERVO_DIGITAL: - summary.append(tr("Digital Servos (333 Hz)")); - break; - default: summary.append(tr("Unknown")); } + if (getVehicleSubType() == MULTI_ROTOR_TRI_Y || getVehicleType() == VEHICLE_FIXEDWING) { + summary.append("
"); + summary.append("").append(tr("Servo type: ")).append(""); + switch (getServoType()) { + case SERVO_ANALOG: + summary.append(tr("Analog Servos (50 Hz)")); + break; + case SERVO_DIGITAL: + summary.append(tr("Digital Servos (333 Hz)")); + break; + default: + summary.append(tr("Unknown")); + } + } + /* summary.append("
"); summary.append("").append(tr("Reboot required: ")).append(""); @@ -344,8 +357,8 @@ void SetupWizard::createPages() setPage(PAGE_HELI, new HeliPage(this)); setPage(PAGE_SURFACE, new SurfacePage(this)); setPage(PAGE_INPUT, new InputPage(this)); - setPage(PAGE_OUTPUT, new OutputPage(this)); - setPage(PAGE_OUTPUT_FIXEDWING, new OutputFixedwingPage(this)); + setPage(PAGE_ESC, new EscPage(this)); + setPage(PAGE_SERVO, new ServoPage(this)); setPage(PAGE_BIAS_CALIBRATION, new BiasCalibrationPage(this)); // setPage(PAGE_REVO_CALIBRATION, new RevoCalibrationPage(this)); setPage(PAGE_OUTPUT_CALIBRATION, new OutputCalibrationPage(this)); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h index d914b994c..b19323559 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -78,15 +78,24 @@ public: return m_inputType; } - void setActuatorType(SetupWizard::ACTUATOR_TYPE type) + void setEscType(SetupWizard::ESC_TYPE type) { m_escType = type; } - SetupWizard::ACTUATOR_TYPE getActuatorType() const + SetupWizard::ESC_TYPE getEscType() const { return m_escType; } + void setServoType(SetupWizard::SERVO_TYPE type) + { + m_servoType = type; + } + SetupWizard::SERVO_TYPE getServoType() const + { + return m_servoType; + } + void setGPSSetting(SetupWizard::GPS_SETTING setting) { m_gpsSetting = setting; @@ -156,8 +165,8 @@ private slots: void pageChanged(int currId); private: enum { PAGE_START, PAGE_CONTROLLER, PAGE_VEHICLES, PAGE_MULTI, PAGE_FIXEDWING, - PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_OUTPUT, PAGE_OUTPUT_FIXEDWING, - PAGE_BIAS_CALIBRATION,PAGE_REVO_CALIBRATION, PAGE_OUTPUT_CALIBRATION, + PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_ESC, PAGE_SERVO, + PAGE_BIAS_CALIBRATION, PAGE_REVO_CALIBRATION, PAGE_OUTPUT_CALIBRATION, PAGE_SAVE, PAGE_SUMMARY, PAGE_NOTYETIMPLEMENTED, PAGE_AIRFRAMESTAB_FIXEDWING, PAGE_REBOOT, PAGE_END, PAGE_UPDATE }; void createPages(); @@ -168,7 +177,8 @@ private: VEHICLE_TYPE m_vehicleType; VEHICLE_SUB_TYPE m_vehicleSubType; INPUT_TYPE m_inputType; - ACTUATOR_TYPE m_escType; + ESC_TYPE m_escType; + SERVO_TYPE m_servoType; GPS_SETTING m_gpsSetting; RADIO_SETTING m_radioSetting; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index e6b32a913..d415c374a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -22,7 +22,6 @@ HEADERS += setupwizardplugin.h \ pages/helipage.h \ pages/surfacepage.h \ pages/abstractwizardpage.h \ - pages/outputpage.h \ pages/inputpage.h \ pages/summarypage.h \ vehicleconfigurationsource.h \ @@ -36,8 +35,9 @@ HEADERS += setupwizardplugin.h \ pages/revocalibrationpage.h \ biascalibrationutil.h \ pages/biascalibrationpage.h \ - pages/outputfixedwingpage.h \ - pages/airframestabfixedwingpage.h + pages/airframestabfixedwingpage.h \ + pages/escpage.h \ + pages/servopage.h SOURCES += setupwizardplugin.cpp \ setupwizard.cpp \ @@ -51,7 +51,6 @@ SOURCES += setupwizardplugin.cpp \ pages/helipage.cpp \ pages/surfacepage.cpp \ pages/abstractwizardpage.cpp \ - pages/outputpage.cpp \ pages/inputpage.cpp \ pages/summarypage.cpp \ vehicleconfigurationsource.cpp \ @@ -65,8 +64,9 @@ SOURCES += setupwizardplugin.cpp \ pages/revocalibrationpage.cpp \ biascalibrationutil.cpp \ pages/biascalibrationpage.cpp \ - pages/outputfixedwingpage.cpp \ - pages/airframestabfixedwingpage.cpp + pages/airframestabfixedwingpage.cpp \ + pages/escpage.cpp \ + pages/servopage.cpp OTHER_FILES += SetupWizard.pluginspec @@ -80,7 +80,6 @@ FORMS += \ pages/fixedwingpage.ui \ pages/helipage.ui \ pages/surfacepage.ui \ - pages/outputpage.ui \ pages/inputpage.ui \ pages/summarypage.ui \ connectiondiagram.ui \ @@ -90,8 +89,9 @@ FORMS += \ pages/autoupdatepage.ui \ pages/revocalibrationpage.ui \ pages/biascalibrationpage.ui \ - pages/outputfixedwingpage.ui \ - pages/airframestabfixedwingpage.ui + pages/airframestabfixedwingpage.ui \ + pages/escpage.ui \ + pages/servopage.ui RESOURCES += \ wizardResources.qrc diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 185d0b1fb..ee52e2504 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -253,6 +253,30 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() { ActuatorSettings *actSettings = ActuatorSettings::GetInstance(m_uavoManager); + qint16 escFrequence = LEGACY_ESC_FREQUENCE; + switch (m_configSource->getEscType()) { + case VehicleConfigurationSource::ESC_LEGACY: + escFrequence = LEGACY_ESC_FREQUENCE; + break; + case VehicleConfigurationSource::ESC_RAPID: + escFrequence = RAPID_ESC_FREQUENCE; + break; + default: + break; + } + + qint16 servoFrequence = ANALOG_SERVO_FREQUENCE; + switch (m_configSource->getServoType()) { + case VehicleConfigurationSource::SERVO_ANALOG: + servoFrequence = ANALOG_SERVO_FREQUENCE; + break; + case VehicleConfigurationSource::SERVO_DIGITAL: + servoFrequence = DIGITAL_SERVO_FREQUENCE; + break; + default: + break; + } + switch (m_configSource->getVehicleType()) { case VehicleConfigurationSource::VEHICLE_MULTI: { @@ -273,31 +297,28 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() data.ChannelUpdateFreq[i] = LEGACY_ESC_FREQUENCE; } - qint16 updateFrequence = LEGACY_ESC_FREQUENCE; - switch (m_configSource->getActuatorType()) { - case VehicleConfigurationSource::ESC_LEGACY: - updateFrequence = LEGACY_ESC_FREQUENCE; - break; - case VehicleConfigurationSource::ESC_RAPID: - updateFrequence = RAPID_ESC_FREQUENCE; - break; - default: - break; - } - switch (m_configSource->getVehicleSubType()) { case VehicleConfigurationSource::MULTI_ROTOR_TRI_Y: - data.ChannelUpdateFreq[0] = updateFrequence; - if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) { - data.ChannelUpdateFreq[1] = updateFrequence; + // Servo always on channel 4 + data.ChannelUpdateFreq[0] = escFrequence; + if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_CC || + m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_CC3D) { + data.ChannelUpdateFreq[1] = servoFrequence; + } else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) { + data.ChannelUpdateFreq[1] = escFrequence; + data.ChannelUpdateFreq[2] = servoFrequence; + } else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { + data.ChannelUpdateFreq[1] = escFrequence; + data.ChannelUpdateFreq[2] = escFrequence; + data.ChannelUpdateFreq[3] = servoFrequence; } break; case VehicleConfigurationSource::MULTI_ROTOR_QUAD_X: case VehicleConfigurationSource::MULTI_ROTOR_QUAD_PLUS: - data.ChannelUpdateFreq[0] = updateFrequence; - data.ChannelUpdateFreq[1] = updateFrequence; + data.ChannelUpdateFreq[0] = escFrequence; + data.ChannelUpdateFreq[1] = escFrequence; if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) { - data.ChannelUpdateFreq[2] = updateFrequence; + data.ChannelUpdateFreq[2] = escFrequence; } break; case VehicleConfigurationSource::MULTI_ROTOR_HEXA: @@ -309,10 +330,10 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X: case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_PLUS: case VehicleConfigurationSource::MULTI_ROTOR_OCTO_V: - data.ChannelUpdateFreq[0] = updateFrequence; - data.ChannelUpdateFreq[1] = updateFrequence; - data.ChannelUpdateFreq[2] = updateFrequence; - data.ChannelUpdateFreq[3] = updateFrequence; + data.ChannelUpdateFreq[0] = escFrequence; + data.ChannelUpdateFreq[1] = escFrequence; + data.ChannelUpdateFreq[2] = escFrequence; + data.ChannelUpdateFreq[3] = escFrequence; break; default: break; @@ -335,27 +356,15 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() data.ChannelMax[i] = actuatorSettings[i].channelMax; } - qint16 updateFrequence = ANALOG_SERVO_FREQUENCE; - switch (m_configSource->getActuatorType()) { - case VehicleConfigurationSource::SERVO_ANALOG: - updateFrequence = ANALOG_SERVO_FREQUENCE; - break; - case VehicleConfigurationSource::SERVO_DIGITAL: - updateFrequence = DIGITAL_SERVO_FREQUENCE; - break; - default: - break; - } - for (quint16 i = 0; i < ActuatorSettings::CHANNELUPDATEFREQ_NUMELEM; i++) { - data.ChannelUpdateFreq[i] = updateFrequence; + data.ChannelUpdateFreq[i] = servoFrequence; if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) { if (i == 1) { - data.ChannelUpdateFreq[i] = ANALOG_SERVO_FREQUENCE; + data.ChannelUpdateFreq[i] = escFrequence; } } else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { if (i == 2) { - data.ChannelUpdateFreq[i] = ANALOG_SERVO_FREQUENCE; + data.ChannelUpdateFreq[i] = escFrequence; } } } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index d03a75356..2d25bcf44 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -61,7 +61,8 @@ public: MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_X, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, MULTI_ROTOR_OCTO_X, MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, FIXED_WING_AILERON, FIXED_WING_VTAIL, FIXED_WING_ELEVON, HELI_CCPM }; - enum ACTUATOR_TYPE { ESC_RAPID, ESC_LEGACY, SERVO_ANALOG, SERVO_DIGITAL, ESC_UNKNOWN }; + enum ESC_TYPE { ESC_RAPID, ESC_LEGACY, ESC_UNKNOWN }; + enum SERVO_TYPE { SERVO_ANALOG, SERVO_DIGITAL, SERVO_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN }; enum GPS_SETTING { GPS_UBX, GPS_NMEA, GPS_DISABLED }; @@ -71,7 +72,8 @@ public: virtual VehicleConfigurationSource::VEHICLE_TYPE getVehicleType() const = 0; virtual VehicleConfigurationSource::VEHICLE_SUB_TYPE getVehicleSubType() const = 0; virtual VehicleConfigurationSource::INPUT_TYPE getInputType() const = 0; - virtual VehicleConfigurationSource::ACTUATOR_TYPE getActuatorType() const = 0; + virtual VehicleConfigurationSource::ESC_TYPE getEscType() const = 0; + virtual VehicleConfigurationSource::SERVO_TYPE getServoType() const = 0; virtual VehicleConfigurationSource::GPS_SETTING getGPSSetting() const = 0; virtual VehicleConfigurationSource::RADIO_SETTING getRadioSetting() const = 0; From a5b8f76345ad217266345ff9d06f0756ee725741 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Fri, 22 Aug 2014 11:47:42 +1000 Subject: [PATCH 055/203] Update SVG for new output numbers, add standard fixed wig graphic which uses single aileron servo --- .../resources/fixedwing-shapes.svg | 6432 ++++++++++------- 1 file changed, 3975 insertions(+), 2457 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg index 0ed305c34..1b62f40f9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg @@ -15,1430 +15,2510 @@ x="0px" y="0px" width="792" - height="2016" - viewBox="0 0 792 2016" + height="2400" + viewBox="0 0 792 2400" enable-background="new 0 0 792 1008" xml:space="preserve" - inkscape:version="0.48.4 r9939" + inkscape:version="0.48.5 r10040" sodipodi:docname="fixedwing-shapes.svg">image/svg+xmlimage/svg+xml +6 + + + + + + + + + + + + + +4 + + +5 - - - - - + + + +4 -4 + + d="m 219.666,638.477 h -0.689 c 0.117,-0.303 0.189,-0.639 0.189,-1 0,-1.24 -0.783,-2.25 -1.75,-2.25 -0.966,0 -1.75,1.01 -1.75,2.25 0,0.361 0.072,0.697 0.19,1 h -2.464 c 0.117,-0.303 0.189,-0.639 0.189,-1 0,-1.24 -0.783,-2.25 -1.75,-2.25 -0.966,0 -1.75,1.01 -1.75,2.25 0,0.361 0.072,0.697 0.19,1 h -1.022 c -0.553,0 -1,-0.446 -1,-1 v -3.584 c 0,-0.552 0.447,-1 1,-1 h 10.416 c 0.553,0 1,0.448 1,1 v 3.584 c 0.001,0.551 -0.446,1 -0.999,1 z" + id="path3835-5" /> \ No newline at end of file From 9dbd2044c8705775a3e6e7a18408167f050222fa Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sat, 23 Aug 2014 00:17:57 +1000 Subject: [PATCH 056/203] Group FW images correctly --- .../resources/fixedwing-shapes.svg | 2702 +++++++++-------- 1 file changed, 1371 insertions(+), 1331 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg index 1b62f40f9..5812cdc9d 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg @@ -740,7 +740,34 @@ gradientTransform="matrix(-87.495651,87.495651,-87.495651,-87.495651,-100821.54,-137203.13)" cx="215.5444" cy="-1372.853" - r="0.90990001" />6 - - - - - - - - - - - - - + id="stop4081" /> 4 - - -6 + + + + + + + + + + + + + + + + + +4 + + + + + xml:space="preserve" + style="font-size:24px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;font-family:Sans" + x="340" + y="1710.3125" + id="text9099-3" + sodipodi:linespacing="125%" + transform="matrix(1.1323794,0,0,1.1323794,-131.41919,-1584.9665)"> + + xml:space="preserve" + style="font-size:24px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;font-family:Sans" + x="339.91922" + y="1709.9094" + id="text9103-2" + sodipodi:linespacing="125%" + transform="matrix(1.1323794,0,0,1.1323794,-131.41919,-1584.9665)"> + + xml:space="preserve" + style="font-size:28px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;font-family:Sans" + x="340.15253" + y="1709.0928" + id="text9107-1" + sodipodi:linespacing="125%" + transform="matrix(1.1323794,0,0,1.1323794,-131.41919,-1584.9665)"> + + xml:space="preserve" + style="font-size:24px;font-style:normal;font-weight:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;font-family:Sans" + x="341.36118" + y="1710.3545" + id="text9111-9" + sodipodi:linespacing="125%" + transform="matrix(1.1323794,0,0,1.1323794,-131.41919,-1584.9665)"> + 4 + id="g9119-8">4 + Date: Sat, 23 Aug 2014 01:01:01 +1000 Subject: [PATCH 057/203] Start basics of single Aileron type support, here be dragons and some SVG known issues --- .../plugins/setupwizard/connectiondiagram.cpp | 8 +- .../setupwizard/pages/fixedwingpage.cpp | 15 +-- .../pages/outputcalibrationpage.cpp | 13 ++- .../src/plugins/setupwizard/setupwizard.cpp | 6 +- .../vehicleconfigurationhelper.cpp | 92 +++++++++++++++---- .../setupwizard/vehicleconfigurationhelper.h | 1 + .../setupwizard/vehicleconfigurationsource.h | 2 +- 7 files changed, 104 insertions(+), 33 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp index 049407727..8a3bc6ae8 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -122,15 +122,15 @@ void ConnectionDiagram::setupGraphicsScene() break; case VehicleConfigurationSource::VEHICLE_FIXEDWING: switch (m_configSource->getVehicleSubType()) { - case VehicleConfigurationSource::FIXED_WING_AILERON: + case VehicleConfigurationSource::FIXED_WING_DUAL_AILERON: elementsToShow << "aileron"; break; + case VehicleConfigurationSource::FIXED_WING_AILERON: + elementsToShow << "ail2"; + break; case VehicleConfigurationSource::FIXED_WING_ELEVON: elementsToShow << "elevon"; break; - case VehicleConfigurationSource::FIXED_WING_VTAIL: - elementsToShow << "vtail"; - break; default: break; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index cb832267a..fb637750d 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -82,8 +82,11 @@ void FixedWingPage::resizeEvent(QResizeEvent *event) void FixedWingPage::setupFixedWingTypesCombo() { - ui->typeCombo->addItem(tr("Aileron, Elevator, Rudder"), SetupWizard::FIXED_WING_AILERON); - m_descriptions << tr("This setup currently expects a traditional 4 channel setup including two ailerons (not connected by Y adapter), an elevator and a rudder. "); + ui->typeCombo->addItem(tr("Dual Aileron Servos"), SetupWizard::FIXED_WING_DUAL_AILERON); + m_descriptions << tr("This setup expects a traditional airframe setup using two independent aileron servos on their own channel (not connected by Y adapter), an elevator and a rudder. "); + + ui->typeCombo->addItem(tr("Single Aileron Servo"), SetupWizard::FIXED_WING_AILERON); + m_descriptions << tr("This setup expects a traditional airframe setup using a single alieron servo or two connected by Y a adapter, an elevator and a rudder. "); ui->typeCombo->addItem(tr("Elevon"), SetupWizard::FIXED_WING_ELEVON); m_descriptions << tr("This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet supported. Setup should include only two elevons, and should explicitly not include a rudder."); @@ -102,15 +105,15 @@ void FixedWingPage::updateImageAndDescription() QString description = m_descriptions.at(ui->typeCombo->currentIndex()); switch (type) { - case SetupWizard::FIXED_WING_AILERON: + case SetupWizard::FIXED_WING_DUAL_AILERON: elementId = "aileron"; break; + case SetupWizard::FIXED_WING_AILERON: + elementId = "ail2"; + break; case SetupWizard::FIXED_WING_ELEVON: elementId = "elevon"; break; -// case SetupWizard::FIXED_WING_VTAIL: -// elementId = "vtail"; -// break; default: elementId = ""; break; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 4affe5c19..68af79f5a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -172,7 +172,7 @@ void OutputCalibrationPage::setupVehicle() setupActuatorMinMaxAndNeutral(0, 5, 6); break; // Fixed Wing - case SetupWizard::FIXED_WING_AILERON: + case SetupWizard::FIXED_WING_DUAL_AILERON: loadSVGFile(FIXEDWING_SVG_FILE); m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4; m_vehicleElementIds << "aileron" << "aileron-frame" << "aileron-motor" << "aileron-ail-left" << "aileron-ail-right" << "aileron-rudder" << "aileron-elevator"; @@ -181,6 +181,17 @@ void OutputCalibrationPage::setupVehicle() setupActuatorMinMaxAndNeutral(3, 3, 5); + getWizard()->setActuatorSettings(m_actuatorSettings); + break; + case SetupWizard::FIXED_WING_AILERON: + loadSVGFile(FIXEDWING_SVG_FILE); + m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4; + m_vehicleElementIds << "ail2" << "ail2-frame" << "ail2-motor" << "ail2-ail-left" << "ail2-ail-right" << "ail2-rudder" << "ail2-elevator"; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3 << 4 << 4 << 4 << 5 << 5 << 5; + m_channelIndex << 0 << 2 << 0 << 0 << 0 << 1 << 1 << 1 << 3 << 3 << 3 << 4 << 4 << 4; + + setupActuatorMinMaxAndNeutral(3, 3, 5); + getWizard()->setActuatorSettings(m_actuatorSettings); break; case SetupWizard::FIXED_WING_ELEVON: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 02e1ef260..d79eccdae 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -260,15 +260,15 @@ QString SetupWizard::getSummaryText() summary.append("
"); summary.append("").append(tr("Vehicle sub type: ")).append(""); switch (getVehicleSubType()) { + case SetupWizard::FIXED_WING_DUAL_AILERON: + summary.append(tr("Dual Aileron")); + break; case SetupWizard::FIXED_WING_AILERON: summary.append(tr("Aileron")); break; case SetupWizard::FIXED_WING_ELEVON: summary.append(tr("Elevon")); break; -// case SetupWizard::FIXED_WING_VTAIL: -// summary.append(tr("Vtail")); -// break; default: summary.append(tr("Unknown")); break; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index ee52e2504..b30c2a3ee 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -224,15 +224,15 @@ void VehicleConfigurationHelper::applyVehicleConfiguration() case VehicleConfigurationSource::VEHICLE_FIXEDWING: { switch (m_configSource->getVehicleSubType()) { + case VehicleConfigurationSource::FIXED_WING_DUAL_AILERON: + setupDualAileron(); + break; case VehicleConfigurationSource::FIXED_WING_AILERON: setupAileron(); break; case VehicleConfigurationSource::FIXED_WING_ELEVON: setupElevon(); break; - case VehicleConfigurationSource::FIXED_WING_VTAIL: - // TODO: Implement settings for VTail fixed wings - break; default: break; } @@ -1582,6 +1582,66 @@ void VehicleConfigurationHelper::setupElevon() applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON, guiSettings); } +void VehicleConfigurationHelper::setupDualAileron() +{ + // Typical vehicle setup + // 1. Setup mixer data + // 2. Setup GUI data + // 3. Apply changes + + mixerChannelSettings channels[10]; + GUIConfigDataUnion guiSettings = getGUIConfigData(); + + // Motor (Chan 3) + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = 0; + channels[2].pitch = 0; + channels[2].yaw = 0; + + // Aileron Servo 1 (Chan 1) + channels[0].type = MIXER_TYPE_SERVO; + channels[0].throttle1 = 0; + channels[0].throttle2 = 0; + channels[0].roll = -100; + channels[0].pitch = 0; + channels[0].yaw = 0; + + // Aileron Servo 2 (Chan 6) + channels[5].type = MIXER_TYPE_SERVO; + channels[5].throttle1 = 0; + channels[5].throttle2 = 0; + channels[5].roll = 100; + channels[5].pitch = 0; + channels[5].yaw = 0; + + // Elevator Servo (Chan 2) + channels[1].type = MIXER_TYPE_SERVO; + channels[1].throttle1 = 0; + channels[1].throttle2 = 0; + channels[1].roll = 0; + channels[1].pitch = 100; + channels[1].yaw = 0; + + // Rudder Servo (Chan 4) + channels[3].type = MIXER_TYPE_SERVO; + channels[3].throttle1 = 0; + channels[3].throttle2 = 0; + channels[3].roll = 0; + channels[3].pitch = 0; + channels[3].yaw = 100; + + guiSettings.fixedwing.FixedWingThrottle = 3; + guiSettings.fixedwing.FixedWingRoll1 = 1; + guiSettings.fixedwing.FixedWingRoll2 = 6; + guiSettings.fixedwing.FixedWingPitch1 = 2; + guiSettings.fixedwing.FixedWingYaw1 = 4; + + applyMixerConfiguration(channels); + applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWING, guiSettings); +} + void VehicleConfigurationHelper::setupAileron() { // Typical vehicle setup @@ -1592,6 +1652,7 @@ void VehicleConfigurationHelper::setupAileron() mixerChannelSettings channels[10]; GUIConfigDataUnion guiSettings = getGUIConfigData(); + // Motor (Chan 3) channels[2].type = MIXER_TYPE_MOTOR; channels[2].throttle1 = 100; channels[2].throttle2 = 0; @@ -1599,39 +1660,34 @@ void VehicleConfigurationHelper::setupAileron() channels[2].pitch = 0; channels[2].yaw = 0; + // Aileron Servo (Chan 1) channels[0].type = MIXER_TYPE_SERVO; channels[0].throttle1 = 0; channels[0].throttle2 = 0; - channels[0].roll = -100; + channels[0].roll = 100; channels[0].pitch = 0; channels[0].yaw = 0; + // Elevator Servo (Chan 2) channels[1].type = MIXER_TYPE_SERVO; channels[1].throttle1 = 0; channels[1].throttle2 = 0; - channels[1].roll = 100; - channels[1].pitch = 0; + channels[1].roll = 0; + channels[1].pitch = 100; channels[1].yaw = 0; + // Rudder Servo (Chan 4) channels[3].type = MIXER_TYPE_SERVO; channels[3].throttle1 = 0; channels[3].throttle2 = 0; channels[3].roll = 0; - channels[3].pitch = 100; - channels[3].yaw = 0; - - channels[4].type = MIXER_TYPE_SERVO; - channels[4].throttle1 = 0; - channels[4].throttle2 = 0; - channels[4].roll = 0; - channels[4].pitch = 0; - channels[4].yaw = 100; + channels[3].pitch = 0; + channels[3].yaw = 100; guiSettings.fixedwing.FixedWingThrottle = 3; guiSettings.fixedwing.FixedWingRoll1 = 1; - guiSettings.fixedwing.FixedWingRoll2 = 2; - guiSettings.fixedwing.FixedWingPitch1 = 4; - guiSettings.fixedwing.FixedWingYaw1 = 5; + guiSettings.fixedwing.FixedWingPitch1 = 2; + guiSettings.fixedwing.FixedWingYaw1 = 4; applyMixerConfiguration(channels); applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWING, guiSettings); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h index 91c244121..f54e7e2b1 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h @@ -108,6 +108,7 @@ private: void setupOctoCopter(); void setupVtail(); void setupElevon(); + void setupDualAileron(); void setupAileron(); private slots: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 2d25bcf44..a09ceba64 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -60,7 +60,7 @@ public: enum VEHICLE_SUB_TYPE { MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS, MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_X, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, MULTI_ROTOR_OCTO_X, MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, - FIXED_WING_AILERON, FIXED_WING_VTAIL, FIXED_WING_ELEVON, HELI_CCPM }; + FIXED_WING_DUAL_AILERON, FIXED_WING_AILERON, FIXED_WING_ELEVON, HELI_CCPM }; enum ESC_TYPE { ESC_RAPID, ESC_LEGACY, ESC_UNKNOWN }; enum SERVO_TYPE { SERVO_ANALOG, SERVO_DIGITAL, SERVO_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN }; From e4a4f35178dd9a4d5a278f28a165c16bfc33f8a9 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sat, 23 Aug 2014 02:00:11 +1000 Subject: [PATCH 058/203] Summary to not show unknown ESC type fpr FWs, remane legacy ESC to standard ESC, summary shows "legacy" still for Multis. Remaining problems appear to be SVG ID related. --- .../plugins/setupwizard/connectiondiagram.cpp | 2 +- .../src/plugins/setupwizard/pages/escpage.cpp | 2 +- .../setupwizard/pages/fixedwingpage.cpp | 10 ++++----- .../pages/outputcalibrationpage.cpp | 2 +- .../resources/fixedwing-shapes.svg | 21 +++++++++++++----- .../src/plugins/setupwizard/setupwizard.cpp | 22 +++++++++++-------- .../vehicleconfigurationhelper.cpp | 5 ++++- .../setupwizard/vehicleconfigurationhelper.h | 1 - .../setupwizard/vehicleconfigurationsource.h | 2 +- 9 files changed, 42 insertions(+), 25 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp index 8a3bc6ae8..6f56f791c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -126,7 +126,7 @@ void ConnectionDiagram::setupGraphicsScene() elementsToShow << "aileron"; break; case VehicleConfigurationSource::FIXED_WING_AILERON: - elementsToShow << "ail2"; + elementsToShow << "aileron-single"; break; case VehicleConfigurationSource::FIXED_WING_ELEVON: elementsToShow << "elevon"; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.cpp index 75d8d6c77..4cb190b32 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.cpp @@ -47,7 +47,7 @@ bool EscPage::validatePage() if (ui->rapidESCButton->isChecked()) { getWizard()->setEscType(SetupWizard::ESC_RAPID); } else { - getWizard()->setEscType(SetupWizard::ESC_LEGACY); + getWizard()->setEscType(SetupWizard::ESC_STANDARD); } return true; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index fb637750d..0e392bd56 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -82,11 +82,11 @@ void FixedWingPage::resizeEvent(QResizeEvent *event) void FixedWingPage::setupFixedWingTypesCombo() { - ui->typeCombo->addItem(tr("Dual Aileron Servos"), SetupWizard::FIXED_WING_DUAL_AILERON); - m_descriptions << tr("This setup expects a traditional airframe setup using two independent aileron servos on their own channel (not connected by Y adapter), an elevator and a rudder. "); + ui->typeCombo->addItem(tr("Aileron Dual Servos"), SetupWizard::FIXED_WING_DUAL_AILERON); + m_descriptions << tr("This setup expects a traditional airframe using two independent aileron servos on their own channel (not connected by Y adapter) plus an elevator and a rudder. "); - ui->typeCombo->addItem(tr("Single Aileron Servo"), SetupWizard::FIXED_WING_AILERON); - m_descriptions << tr("This setup expects a traditional airframe setup using a single alieron servo or two connected by Y a adapter, an elevator and a rudder. "); + ui->typeCombo->addItem(tr("Aileron Single Servo"), SetupWizard::FIXED_WING_AILERON); + m_descriptions << tr("This setup expects a traditional airframe using a single alieron servo or two servos connected by a Y adapter plus an elevator and a rudder. "); ui->typeCombo->addItem(tr("Elevon"), SetupWizard::FIXED_WING_ELEVON); m_descriptions << tr("This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet supported. Setup should include only two elevons, and should explicitly not include a rudder."); @@ -109,7 +109,7 @@ void FixedWingPage::updateImageAndDescription() elementId = "aileron"; break; case SetupWizard::FIXED_WING_AILERON: - elementId = "ail2"; + elementId = "aileron-single"; break; case SetupWizard::FIXED_WING_ELEVON: elementId = "elevon"; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 68af79f5a..4865e9b13 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -186,7 +186,7 @@ void OutputCalibrationPage::setupVehicle() case SetupWizard::FIXED_WING_AILERON: loadSVGFile(FIXEDWING_SVG_FILE); m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4; - m_vehicleElementIds << "ail2" << "ail2-frame" << "ail2-motor" << "ail2-ail-left" << "ail2-ail-right" << "ail2-rudder" << "ail2-elevator"; + m_vehicleElementIds << "aileron-single" << "ail2-frame" << "ail2-motor" << "ail2-ail-left" << "ail2-ail-right" << "ail2-rudder" << "ail2-elevator"; m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3 << 4 << 4 << 4 << 5 << 5 << 5; m_channelIndex << 0 << 2 << 0 << 0 << 0 << 1 << 1 << 1 << 3 << 3 << 3 << 4 << 4 << 4; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg index 5812cdc9d..968c38041 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg @@ -777,14 +777,14 @@ inkscape:pageopacity="0" inkscape:pageshadow="2" inkscape:window-width="1920" - inkscape:window-height="1017" + inkscape:window-height="1080" id="namedview4099" showgrid="false" inkscape:zoom="0.72183815" inkscape:cx="658.07866" - inkscape:cy="230.01827" - inkscape:window-x="-8" - inkscape:window-y="-8" + inkscape:cy="562.50278" + inkscape:window-x="0" + inkscape:window-y="0" inkscape:window-maximized="1" inkscape:current-layer="Layer_1" showborder="true" @@ -2581,6 +2581,7 @@ x="569.97363" y="1401.7424">6 +
+ + + + 4 + "); summary.append("").append(tr("Speed Controller (ESC) type: ")).append(""); - switch (getEscType()) { - case ESC_LEGACY: - summary.append(tr("Legacy ESC (50 Hz)")); - break; - case ESC_RAPID: - summary.append(tr("Rapid ESC (400 Hz)")); - break; - default: - summary.append(tr("Unknown")); + if (getVehicleType() == VEHICLE_FIXEDWING) { + summary.append(tr("Standard ESC (50 Hz)")); + } else { + switch (getEscType()) { + case ESC_STANDARD: + summary.append(tr("Legacy ESC (50 Hz)")); + break; + case ESC_RAPID: + summary.append(tr("Rapid ESC (400 Hz)")); + break; + default: + summary.append(tr("Unknown")); + } } if (getVehicleSubType() == MULTI_ROTOR_TRI_Y || getVehicleType() == VEHICLE_FIXEDWING) { diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index b30c2a3ee..148604c47 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -255,7 +255,7 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() qint16 escFrequence = LEGACY_ESC_FREQUENCE; switch (m_configSource->getEscType()) { - case VehicleConfigurationSource::ESC_LEGACY: + case VehicleConfigurationSource::ESC_STANDARD: escFrequence = LEGACY_ESC_FREQUENCE; break; case VehicleConfigurationSource::ESC_RAPID: @@ -1553,6 +1553,7 @@ void VehicleConfigurationHelper::setupElevon() mixerChannelSettings channels[10]; GUIConfigDataUnion guiSettings = getGUIConfigData(); + // Motor (Chan 3) channels[2].type = MIXER_TYPE_MOTOR; channels[2].throttle1 = 100; channels[2].throttle2 = 0; @@ -1560,6 +1561,7 @@ void VehicleConfigurationHelper::setupElevon() channels[2].pitch = 0; channels[2].yaw = 0; + // Elevon Servo 1 (Chan 1) channels[0].type = MIXER_TYPE_SERVO; channels[0].throttle1 = 0; channels[0].throttle2 = 0; @@ -1567,6 +1569,7 @@ void VehicleConfigurationHelper::setupElevon() channels[0].pitch = 100; channels[0].yaw = 0; + // Elevon Servo 1 (Chan 2) channels[1].type = MIXER_TYPE_SERVO; channels[1].throttle1 = 0; channels[1].throttle2 = 0; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h index f54e7e2b1..49dee8ec5 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h @@ -106,7 +106,6 @@ private: void setupQuadCopter(); void setupHexaCopter(); void setupOctoCopter(); - void setupVtail(); void setupElevon(); void setupDualAileron(); void setupAileron(); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index a09ceba64..2102bf4d9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -61,7 +61,7 @@ public: MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_X, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, MULTI_ROTOR_OCTO_X, MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, FIXED_WING_DUAL_AILERON, FIXED_WING_AILERON, FIXED_WING_ELEVON, HELI_CCPM }; - enum ESC_TYPE { ESC_RAPID, ESC_LEGACY, ESC_UNKNOWN }; + enum ESC_TYPE { ESC_RAPID, ESC_STANDARD, ESC_UNKNOWN }; enum SERVO_TYPE { SERVO_ANALOG, SERVO_DIGITAL, SERVO_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN }; From 169b95fb4debf5d5d9bf274eefe6ac59e04d1e05 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sat, 23 Aug 2014 04:12:25 +1000 Subject: [PATCH 059/203] Move FWing ESC setting to use the setter. --- .../plugins/setupwizard/pages/vehiclepage.cpp | 1 + .../src/plugins/setupwizard/setupwizard.cpp | 22 ++++++++----------- 2 files changed, 10 insertions(+), 13 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp index a8b1780a9..eac4c9a02 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp @@ -46,6 +46,7 @@ bool VehiclePage::validatePage() getWizard()->setVehicleType(SetupWizard::VEHICLE_MULTI); } else if (ui->fixedwingButton->isChecked()) { getWizard()->setVehicleType(SetupWizard::VEHICLE_FIXEDWING); + getWizard()->setEscType(SetupWizard::ESC_STANDARD); } else if (ui->heliButton->isChecked()) { getWizard()->setVehicleType(SetupWizard::VEHICLE_HELI); } else if (ui->surfaceButton->isChecked()) { diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 2767217b1..c08a1fc28 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -312,19 +312,15 @@ QString SetupWizard::getSummaryText() summary.append("
"); summary.append("").append(tr("Speed Controller (ESC) type: ")).append(""); - if (getVehicleType() == VEHICLE_FIXEDWING) { - summary.append(tr("Standard ESC (50 Hz)")); - } else { - switch (getEscType()) { - case ESC_STANDARD: - summary.append(tr("Legacy ESC (50 Hz)")); - break; - case ESC_RAPID: - summary.append(tr("Rapid ESC (400 Hz)")); - break; - default: - summary.append(tr("Unknown")); - } + switch (getEscType()) { + case ESC_STANDARD: + summary.append(tr("Legacy ESC (50 Hz)")); + break; + case ESC_RAPID: + summary.append(tr("Rapid ESC (400 Hz)")); + break; + default: + summary.append(tr("Unknown")); } if (getVehicleSubType() == MULTI_ROTOR_TRI_Y || getVehicleType() == VEHICLE_FIXEDWING) { From cda94b33191c6b0d690e3b8a3f3a06f39ed2fe32 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sat, 23 Aug 2014 04:30:32 +1000 Subject: [PATCH 060/203] Rename Legacy to Standard, while Legacy for Multis, not so for Fwings an Helis. --- ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index c08a1fc28..d18e59345 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -314,7 +314,7 @@ QString SetupWizard::getSummaryText() summary.append("").append(tr("Speed Controller (ESC) type: ")).append(""); switch (getEscType()) { case ESC_STANDARD: - summary.append(tr("Legacy ESC (50 Hz)")); + summary.append(tr("Standard ESC (50 Hz)")); break; case ESC_RAPID: summary.append(tr("Rapid ESC (400 Hz)")); From 3dc74c8c5901c1928ceb191c973e532dbb275821 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sat, 23 Aug 2014 09:43:30 +1000 Subject: [PATCH 061/203] Not sure if this is needed but updated the Python pri file to reflect the correct version --- ground/openpilotgcs/src/python.pri | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/python.pri b/ground/openpilotgcs/src/python.pri index 3643adc02..a101bfb75 100644 --- a/ground/openpilotgcs/src/python.pri +++ b/ground/openpilotgcs/src/python.pri @@ -1,7 +1,7 @@ # We use python to extract git version info and generate some other files, # but it may be installed locally. The expected python version should be # kept in sync with make/tools.mk. -PYTHON_DIR = qt-5.1.0/Tools/mingw48_32/opt/bin +PYTHON_DIR = qt-5.3.1/Tools/mingw48_32/opt/bin ROOT_DIR = $$GCS_SOURCE_TREE/../.. From 337ab6a436ff72ced8647ec39a4261d44ded0a4e Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sat, 23 Aug 2014 23:36:06 +1000 Subject: [PATCH 062/203] Add servos to image as we will support single servo --- .../src/libs/sdlgamepad/sdlgamepad.pro.user | 178 +- .../config/images/fixedwing-shapes.svg | 1686 ++++++++++------- 2 files changed, 1052 insertions(+), 812 deletions(-) diff --git a/ground/openpilotgcs/src/libs/sdlgamepad/sdlgamepad.pro.user b/ground/openpilotgcs/src/libs/sdlgamepad/sdlgamepad.pro.user index 96217e1ea..05764321a 100644 --- a/ground/openpilotgcs/src/libs/sdlgamepad/sdlgamepad.pro.user +++ b/ground/openpilotgcs/src/libs/sdlgamepad/sdlgamepad.pro.user @@ -1,112 +1,66 @@ - - - - ProjectExplorer.Project.ActiveTarget - 0 - - - ProjectExplorer.Project.EditorSettings - - System - - - - ProjectExplorer.Project.Target.0 - - Desktop - Qt4ProjectManager.Target.DesktopTarget - 0 - 0 - - - qmake - QtProjectManager.QMakeBuildStep - - - - Make - Qt4ProjectManager.MakeStep - false - - - - 2 - - Make - Qt4ProjectManager.MakeStep - true - - clean - - - - 1 - false - - Debug - Qt4ProjectManager.Qt4BuildConfiguration - 2 - /Users/jcotton81/Documents/Programming/OpenPilot/ground/src/plugins/gcscontrol/sdlgamepad-build-desktop - 2 - 0 - true - - - - qmake - QtProjectManager.QMakeBuildStep - - - - Make - Qt4ProjectManager.MakeStep - false - - - - 2 - - Make - Qt4ProjectManager.MakeStep - true - - clean - - - - 1 - false - - Release - Qt4ProjectManager.Qt4BuildConfiguration - 0 - /Users/jcotton81/Documents/Programming/OpenPilot/ground/src/plugins/gcscontrol/sdlgamepad-build-desktop - 2 - 0 - true - - 2 - - - 2 - - false - - - false - $BUILDDIR - Custom Executable - ProjectExplorer.CustomExecutableRunConfiguration - - 1 - - - - ProjectExplorer.Project.TargetCount - 1 - - - ProjectExplorer.Project.Updater.FileVersion - 4 - - + + + + + + ProjectExplorer.Project.ActiveTarget + -1 + + + ProjectExplorer.Project.EditorSettings + + true + false + true + + Cpp + + CppGlobal + + + + QmlJS + + QmlJSGlobal + + + 2 + UTF-8 + false + 4 + false + 80 + true + true + 1 + true + false + 0 + true + 0 + 8 + true + 1 + true + true + true + false + + + + ProjectExplorer.Project.PluginSettings + + + + ProjectExplorer.Project.TargetCount + 0 + + + ProjectExplorer.Project.Updater.EnvironmentId + {6e1a7efe-f107-41f3-9383-31e878c1f556} + + + ProjectExplorer.Project.Updater.FileVersion + 15 + + diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index 52d8f72b5..cb1cb1c44 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -19,7 +19,7 @@ viewBox="0 0 792 2016" enable-background="new 0 0 792 1008" xml:space="preserve" - inkscape:version="0.48.4 r9939" + inkscape:version="0.48.5 r10040" sodipodi:docname="fixedwing-shapes.svg">image/svg+xml + style="fill:none;stroke:#010101;stroke-width:0.69520003;stroke-linecap:round;stroke-linejoin:round" />
\ No newline at end of file From 6c79b5554fcd6374d9555fb3fd97577a3d6feb17 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 24 Aug 2014 00:34:07 +1000 Subject: [PATCH 063/203] Add single servo artwork --- .../config/images/fixedwing-shapes.svg | 1056 ++++++++++++++++- 1 file changed, 1047 insertions(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index cb1cb1c44..4ef1492ea 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -272,7 +272,79 @@ x1="54.208" y1="630.1615" x2="281.74301" - y2="630.1615" />
\ No newline at end of file + points="410.22,718.926 408.966,717.672 410.22,716.418 409.938,716.137 408.685,717.391 407.431,716.137 407.149,716.418 408.403,717.672 407.149,718.926 407.431,719.207 408.685,717.953 409.938,719.207 " + style="fill:#ffffff" /> \ No newline at end of file From b119f7ee5f9c6d8e5c84ddd8fc2c6f92f7b3e5b3 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 24 Aug 2014 00:40:24 +1000 Subject: [PATCH 064/203] Update grouping to show servos --- .../config/images/fixedwing-shapes.svg | 1402 ++++++++--------- 1 file changed, 699 insertions(+), 703 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index 4ef1492ea..d808e7b14 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -359,7 +359,7 @@ showgrid="false" inkscape:zoom="1" inkscape:cx="400.12565" - inkscape:cy="1441.1007" + inkscape:cy="1481.1007" inkscape:window-x="-8" inkscape:window-y="-8" inkscape:window-maximized="1" @@ -932,697 +932,693 @@ id="path8516_1_-1-6" inkscape:connector-curvature="0" style="fill:none;stroke:#010101;stroke-width:0.69520003;stroke-linecap:round;stroke-linejoin:round" /> Date: Sat, 23 Aug 2014 17:50:50 +0200 Subject: [PATCH 065/203] OP-1222 Fixed some groups in svg. Removed translation node in svg by regrouping childs. Fixed fit in view issue in fixedwingpage and some channel setup in outputcalibrationpage. --- .../setupwizard/pages/fixedwingpage.cpp | 23 +- .../plugins/setupwizard/pages/fixedwingpage.h | 3 + .../pages/outputcalibrationpage.cpp | 10 +- .../plugins/setupwizard/pages/vehiclepage.cpp | 4 +- .../resources/fixedwing-shapes.svg | 8098 ++++++++--------- 5 files changed, 4057 insertions(+), 4081 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index 0e392bd56..ab506ccd6 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -45,11 +45,8 @@ FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) : setupFixedWingTypesCombo(); // Default to Aileron setup - ui->typeCombo->setCurrentIndex(0); connect(ui->typeCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateImageAndDescription())); - ui->typeGraphicsView->setSceneRect(m_fixedwingPic->boundingRect()); - ui->typeGraphicsView->fitInView(m_fixedwingPic, Qt::KeepAspectRatio); - + ui->typeCombo->setCurrentIndex(0); } FixedWingPage::~FixedWingPage() @@ -71,15 +68,26 @@ bool FixedWingPage::validatePage() return true; } -void FixedWingPage::resizeEvent(QResizeEvent *event) +void FixedWingPage::fitInView() { - Q_UNUSED(event); if (m_fixedwingPic) { ui->typeGraphicsView->setSceneRect(m_fixedwingPic->boundingRect()); ui->typeGraphicsView->fitInView(m_fixedwingPic, Qt::KeepAspectRatio); } } +void FixedWingPage::resizeEvent(QResizeEvent *event) +{ + Q_UNUSED(event); + fitInView(); +} + +void FixedWingPage::showEvent(QShowEvent *event) +{ + Q_UNUSED(event); + fitInView(); +} + void FixedWingPage::setupFixedWingTypesCombo() { ui->typeCombo->addItem(tr("Aileron Dual Servos"), SetupWizard::FIXED_WING_DUAL_AILERON); @@ -98,8 +106,6 @@ void FixedWingPage::updateAvailableTypes() void FixedWingPage::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()); @@ -125,4 +131,3 @@ void FixedWingPage::updateImageAndDescription() ui->typeDescription->setText(description); } - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h index 593be37bb..5c50adcba 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h @@ -48,8 +48,10 @@ public: void initializePage(); bool validatePage(); + void fitInView(); protected: void resizeEvent(QResizeEvent *event); + void showEvent(QShowEvent *event); private: Ui::FixedWingPage *ui; @@ -60,6 +62,7 @@ private: private slots: void updateImageAndDescription(); + }; #endif // FIXEDWINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 4865e9b13..969d88472 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -185,12 +185,12 @@ void OutputCalibrationPage::setupVehicle() break; case SetupWizard::FIXED_WING_AILERON: loadSVGFile(FIXEDWING_SVG_FILE); - m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4; - m_vehicleElementIds << "aileron-single" << "ail2-frame" << "ail2-motor" << "ail2-ail-left" << "ail2-ail-right" << "ail2-rudder" << "ail2-elevator"; - m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3 << 4 << 4 << 4 << 5 << 5 << 5; - m_channelIndex << 0 << 2 << 0 << 0 << 0 << 1 << 1 << 1 << 3 << 3 << 3 << 4 << 4 << 4; + m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4; + m_vehicleElementIds << "aileron-single" << "ail2-frame" << "ail2-motor" << "ail2-aileron" << "ail2-rudder" << "ail2-elevator"; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3 << 4 << 4 << 4; + m_channelIndex << 0 << 2 << 0 << 0 << 0 << 4 << 4 << 4 << 1 << 1 << 1; - setupActuatorMinMaxAndNeutral(3, 3, 5); + setupActuatorMinMaxAndNeutral(3, 3, 4); getWizard()->setActuatorSettings(m_actuatorSettings); break; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp index eac4c9a02..a9c476cdc 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp @@ -59,6 +59,6 @@ bool VehiclePage::validatePage() void VehiclePage::initializePage() { - ui->fixedwingButton->setEnabled(getWizard()->getControllerType() == SetupWizard::CONTROLLER_REVO || - getWizard()->getControllerType() == SetupWizard::CONTROLLER_NANO); + //ui->fixedwingButton->setEnabled(getWizard()->getControllerType() == SetupWizard::CONTROLLER_REVO || + // getWizard()->getControllerType() == SetupWizard::CONTROLLER_NANO); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg index 968c38041..07d7fe2d0 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg @@ -19,4106 +19,4074 @@ viewBox="0 0 792 2400" enable-background="new 0 0 792 1008" xml:space="preserve" - inkscape:version="0.48.5 r10040" + inkscape:version="0.48.4 r9939" sodipodi:docname="fixedwing-shapes.svg">image/svg+xml - -image/svg+xml6 + + + + +4 +6 - - - - - - - - - - - - - - - - - - - - - - -4 - - - - - - - - - - - - - - - - -4 - - - \ No newline at end of file + height="36.404999" + id="rect3816-4" /> + + + +4 + \ No newline at end of file From 86f8997e8881964b37295b4337f1f6293c98e771 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 24 Aug 2014 01:52:41 +1000 Subject: [PATCH 066/203] Start basics of config plugin page for FW clean up, add support for single servo aileron fixedwings --- .../src/plugins/config/airframe_fixedwing.ui | 43 ++++++------ .../src/plugins/config/airframe_multirotor.ui | 67 +++++++++++++++---- .../configfixedwingwidget.cpp | 30 ++++++--- .../config/configvehicletypewidget.cpp | 8 +-- 4 files changed, 104 insertions(+), 44 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui index 176b5daca..200e1496a 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui @@ -14,19 +14,22 @@ Form
- + + 0 + + + 0 + + + 0 + + 0 - - - - 0 - 0 - - + 75 @@ -34,17 +37,9 @@ - Airplane type: + Airframe Type: - - - - 0 - 0 - - - @@ -64,6 +59,16 @@ + + + + + 0 + 0 + + + + @@ -475,9 +480,7 @@ margin:1px; 1 - - - + elevonSlider1 diff --git a/ground/openpilotgcs/src/plugins/config/airframe_multirotor.ui b/ground/openpilotgcs/src/plugins/config/airframe_multirotor.ui index f740d7df3..8d20353cd 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe_multirotor.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe_multirotor.ui @@ -14,7 +14,16 @@ Form - + + 0 + + + 0 + + + 0 + + 0 @@ -32,10 +41,19 @@ - Frame + Airframe - + + 9 + + + 9 + + + 9 + + 9 @@ -90,7 +108,16 @@ Throttle Curve - + + 9 + + + 9 + + + 9 + + 9 @@ -136,12 +163,21 @@ Mix Level + + 9 + + + 9 + + + 9 + + + 9 + 0 - - 9 - @@ -375,7 +411,7 @@ Typical value is 50% for + or X configuration on quads. - Frame Type: + Airframe Type:
@@ -476,7 +512,16 @@ Typical value is 50% for + or X configuration on quads. Motor output channels
- + + 9 + + + 9 + + + 9 + + 9 @@ -801,9 +846,7 @@ margin:1px; 1 - - - + mrRollMixLevel diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 25306c0af..1a464524b 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -53,11 +53,11 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : populateChannelComboBoxes(); QStringList fixedWingTypes; - fixedWingTypes << "Elevator aileron rudder" << "Elevon"; + fixedWingTypes << "Aileron Dual Servo" << "Aileron Single Servo" << "Elevon"; m_aircraft->fixedWingType->addItems(fixedWingTypes); - // Set default model to "Elevator aileron rudder" - m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); + // Set default model to "Aileron Dual Servo" + m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Aileron Dual Servo")); setupUI(m_aircraft->fixedWingType->currentText()); @@ -135,9 +135,9 @@ void ConfigFixedWingWidget::setupUI(QString frameType) qDebug() << "Current Aircraft type: \n" << m_aircraft->fixedWingType->currentText(); - if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") { + if (frameType == "FixedWing" || frameType == "Aileron Dual Servo") { plane->setElementId("aileron"); - setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevator aileron rudder")); + setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Aileron Dual Servo")); resetChannelboxesAndSliders(); m_aircraft->fwRudder1ChannelBox->setEnabled(true); @@ -151,7 +151,21 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwAileron2Label->setText("Aileron 2"); m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); + } else if (frameType == "Aileron Single Servo") { + plane->setElementId("aileron-single"); + setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Aileron Single Servo")); + resetChannelboxesAndSliders(); + m_aircraft->fwRudder1ChannelBox->setEnabled(true); + m_aircraft->fwRudder2ChannelBox->setEnabled(true); + m_aircraft->fwElevator1ChannelBox->setEnabled(true); + m_aircraft->fwElevator2ChannelBox->setEnabled(true); + m_aircraft->fwAileron1ChannelBox->setEnabled(true); + m_aircraft->fwAileron2ChannelBox->setEnabled(false); + m_aircraft->fwAileron1Label->setText("Aileron 1"); + m_aircraft->fwAileron2Label->setText("Aileron 2"); + m_aircraft->fwElevator1Label->setText("Elevator 1"); + m_aircraft->fwElevator2Label->setText("Elevator 2"); } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { // do nothing for now } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { @@ -202,7 +216,7 @@ void ConfigFixedWingWidget::setupEnabledControls(QString frameType) // enableComboBoxes(this, CHANNELBOXNAME, 3, true); } else if (frameType == "Elevon" || frameType == "Elevon") { enableComboBoxes(this, CHANNELBOXNAME, 3, true); - } else if (frameType == "aileron" || frameType == "Elevator aileron rudder") { + } else if (frameType == "aileron" || frameType == "Aileron Dual Servo" || frameType == "Aileron Single Servo") { enableComboBoxes(this, CHANNELBOXNAME, 4, true); } } @@ -300,7 +314,7 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() QString airframeType; QList motor_servo_List; - if (m_aircraft->fixedWingType->currentText() == "Elevator aileron rudder") { + if (m_aircraft->fixedWingType->currentText() == "Aileron Dual Servo" || "aileron-single") { airframeType = "FixedWing"; setupFrameFixedWing(airframeType); @@ -312,7 +326,7 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); - } + } else if (m_aircraft->fixedWingType->currentText() == "elevon") { airframeType = "FixedWingElevon"; setupFrameElevon(airframeType); diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 50589ae4f..575499753 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -198,8 +198,7 @@ void ConfigVehicleTypeWidget::refreshWidgetsValues(UAVObject *o) UAVObjectField *field = system->getField(QString("AirframeType")); Q_ASSERT(field); - // At this stage, we will need to have some hardcoded settings in this code, this - // is not ideal, but there you go. + // At this stage, we will need to have some hardcoded settings in this code QString frameType = field->getValue().toString(); int category = frameCategory(frameType); @@ -262,8 +261,9 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets() int ConfigVehicleTypeWidget::frameCategory(QString frameType) { - if (frameType == "FixedWing" || frameType == "Elevator aileron rudder" || frameType == "FixedWingElevon" - || frameType == "Elevon" || frameType == "FixedWingVtail" || frameType == "Vtail") { + if (frameType == "FixedWing" || frameType == "Aileron Dual Servo" || frameType == "Aileron Single Servo" + || frameType == "FixedWingElevon" || frameType == "Elevon" || frameType == "FixedWingVtail" + || frameType == "Vtail") { return ConfigVehicleTypeWidget::FIXED_WING; } else if (frameType == "Tri" || frameType == "Tricopter Y" || frameType == "QuadX" || frameType == "Quad X" || frameType == "QuadP" || frameType == "Quad +" || frameType == "Hexa" || frameType == "Hexacopter" From 030736f89ccd2c0c8be7e7e56a31476665776568 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 24 Aug 2014 07:37:59 +1000 Subject: [PATCH 067/203] First draft of totally reworked FixedWing layout for the config plugin --- .../src/plugins/config/airframe_fixedwing.ui | 970 ++++++++++-------- 1 file changed, 555 insertions(+), 415 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui index 200e1496a..492fcafde 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui @@ -13,7 +13,7 @@ Form - + 0 @@ -26,8 +26,310 @@ 0 - - + + + + + 10 + 10 + + + + + 16777215 + 16777215 + + + + Airframe + + + + 9 + + + 9 + + + 9 + + + 9 + + + + + + 0 + 0 + + + + + 10 + 10 + + + + background:transparent + + + QFrame::NoFrame + + + QFrame::Plain + + + + + + + + + + + 0 + 0 + + + + + 10 + 10 + + + + + 16777215 + 16777215 + + + + Throttle Curve + + + + 9 + + + 9 + + + 9 + + + 9 + + + + + + 0 + 0 + + + + + 10 + 10 + + + + + 10 + 10 + + + + + 50 + 50 + + + + + + + + + + + + 16777215 + 16777215 + + + + Elevon Mix + + + + 9 + + + 9 + + + 9 + + + 9 + + + 0 + + + + + + + + 0 + 0 + + + + + 40 + 0 + + + + + 16777215 + 16777215 + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Roll + + + Qt::AlignCenter + + + + + + + + 40 + 0 + + + + Weight of Roll mixing in percent. +Typical values are 100% for + configuration and 50% for X configuration on quads. + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + + 40 + 0 + + + + 50 + + + Qt::AlignCenter + + + + + + + + + + + + 40 + 0 + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Pitch + + + Qt::AlignCenter + + + + + + + + 40 + 0 + + + + Weight of Pitch mixing in percent. +Typical values are 100% for + configuration and 50% for X configuration on quads. + + + 100 + + + 50 + + + Qt::Vertical + + + + + + + + 40 + 0 + + + + 50 + + + Qt::AlignCenter + + + + + + + + + + + + QLayout::SetFixedSize + @@ -42,414 +344,55 @@ - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - - - - - - 0 - 0 - - - - - - - - 0 - - - + - + 0 0 - 230 - 100 + 25 + 25 - - Output Channel Assignments + + + 16777215 + 25 + + + + Select the Multirotor frame type here. - - - QFormLayout::AllNonFixedFieldsGrow - - - - - Engine - - - - - - - Select output channel for the engine - - - - - - - - 60 - 0 - - - - Aileron 1 - - - - - - - Select output channel for the first aileron (or elevon) - - - - - - - true - - - - 60 - 0 - - - - Aileron 2 - - - - - - - true - - - Select output channel for the second aileron (or elevon) - - - - - - - - 67 - 0 - - - - Elevator 1 - - - - - - - Select output channel for the first elevator - - - - - - - true - - - - 67 - 0 - - - - Elevator 2 - - - - - - - true - - - Select output channel for a secondary elevator - - - - - - - Rudder 1 - - - - - - - Select output channel for the first rudder - - - - - - - Rudder 2 - - - - - - - Select output channel for a secondary rudder - - - - - - - - 0 - 0 - - - - Elevon Mix - - - - - - - - - - - 65 - 0 - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Rudder % - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - 100 - - - 50 - - - Qt::Vertical - - - - - - - 50 - - - Qt::AlignCenter - - - - - - - - - - - - 65 - 0 - - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; -font: bold 12px; -margin:1px; - - - Pitch % - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - 100 - - - 50 - - - Qt::Vertical - - - - - - - 50 - - - Qt::AlignCenter - - - - - - - - - - - - - - - 0 - 100 - - - - Throttle Curve - - - - - - - 1 - 1 - - - - - 0 - 0 - - - - - 500 - 500 - - - - - 10 - 10 - - - - - 300 - 350 - - - - - - - - - + Qt::Horizontal - 0 - 20 + 10 + 13 - - - - Qt::Vertical - - - - 20 - 40 - - - - - - + + - + Qt::Horizontal - 40 + 10 20 @@ -457,6 +400,12 @@ margin:1px; + + + 0 + 0 + + 75 @@ -466,10 +415,234 @@ margin:1px; Mixer OK + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + 0 + 0 + + + + + 0 + 140 + + + + Output Channel Assignments + + + + 9 + + + 9 + + + 9 + + + 9 + + + + + QLayout::SetMaximumSize + + + QFormLayout::AllNonFixedFieldsGrow + + + 6 + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Elevator 2 + + + + + + + true + + + + 0 + 0 + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Rudder 1 + + + + + + + true + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Rudder 2 + + + + + + + true + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + + + QLayout::SetMaximumSize + + + QFormLayout::AllNonFixedFieldsGrow + + + 6 + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Motor + + + + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Aileron 1 + + + + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Aileron 2 + + + + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; +font: bold 12px; +margin:1px; + + + Elevator 1 + + + + + + + Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + + + + + + + +
@@ -481,38 +654,5 @@ margin:1px; - - - elevonSlider1 - valueChanged(int) - elevonSliderLabel1 - setNum(int) - - - 124 - 126 - - - 124 - 126 - - - - - elevonSlider2 - valueChanged(int) - elevonSliderLabel2 - setNum(int) - - - 362 - 299 - - - 124 - 126 - - - - +
From 1776802ebd9ef9f30260a34162b11c4e66d0fee4 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 24 Aug 2014 07:57:59 +1000 Subject: [PATCH 068/203] Minor clean up --- .../src/plugins/config/airframe_fixedwing.ui | 26 +++++++++---------- .../src/plugins/config/airframe_multirotor.ui | 4 +-- 2 files changed, 14 insertions(+), 16 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui index 492fcafde..b962b898c 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui @@ -27,7 +27,7 @@ 0 - + 10 @@ -224,8 +224,7 @@ margin:1px; - Weight of Roll mixing in percent. -Typical values are 100% for + configuration and 50% for X configuration on quads. + Weight of mixing in percent 100 @@ -290,8 +289,7 @@ margin:1px; - Weight of Pitch mixing in percent. -Typical values are 100% for + configuration and 50% for X configuration on quads. + Weight of mixing in percent 100 @@ -331,7 +329,7 @@ Typical values are 100% for + configuration and 50% for X configuration on quads QLayout::SetFixedSize - + 75 @@ -364,7 +362,7 @@ Typical values are 100% for + configuration and 50% for X configuration on quads - Select the Multirotor frame type here. + Select Fixed-wing type @@ -489,7 +487,7 @@ margin:1px; - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + Assign your output channel @@ -513,7 +511,7 @@ margin:1px; true - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + Assign your output channel @@ -537,7 +535,7 @@ margin:1px; true - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + Assign your output channel @@ -571,7 +569,7 @@ margin:1px; - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + Assign your motor output channel @@ -592,7 +590,7 @@ margin:1px; - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + Assign your output channel @@ -613,7 +611,7 @@ margin:1px; - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + Assign your output channel @@ -634,7 +632,7 @@ margin:1px; - Assign your motor output channels using the drawing above as a reference. Respect propeller rotation. + Assign your output channel diff --git a/ground/openpilotgcs/src/plugins/config/airframe_multirotor.ui b/ground/openpilotgcs/src/plugins/config/airframe_multirotor.ui index 8d20353cd..4d96dce60 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe_multirotor.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe_multirotor.ui @@ -225,7 +225,7 @@ margin:1px; Weight of Roll mixing in percent. -Typical values are 100% for + configuration and 50% for X configuration on quads. +Typical values are 100% for + configuration and 50% for X configuration on quads 100 @@ -436,7 +436,7 @@ Typical value is 50% for + or X configuration on quads. - Select the Multirotor frame type here. + Select the Multirotor frame type From 57ef5625db2450bf4a57d090dab539debc96323a Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 24 Aug 2014 08:52:42 +1000 Subject: [PATCH 069/203] Add connections --- .../src/plugins/config/airframe_fixedwing.ui | 35 ++++++++++++++++++- 1 file changed, 34 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui index b962b898c..e52e9833a 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui @@ -652,5 +652,38 @@ margin:1px; - + + + elevonSlider1 + valueChanged(int) + elevonSliderLabel1 + setNum(int) + + + 124 + 126 + + + 124 + 126 + + + + + elevonSlider2 + valueChanged(int) + elevonSliderLabel2 + setNum(int) + + + 362 + 299 + + + 124 + 126 + + + + From 8133606453d5aa471b44cf1191971788d1b1a7dd Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sun, 24 Aug 2014 09:18:49 +1000 Subject: [PATCH 070/203] disable Mixer by default --- .../src/plugins/config/airframe_fixedwing.ui | 41 ++++--------------- .../configfixedwingwidget.cpp | 2 + 2 files changed, 9 insertions(+), 34 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui index e52e9833a..4786f9e40 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui @@ -217,6 +217,9 @@ margin:1px; + + false + 40 @@ -282,6 +285,9 @@ margin:1px; + + false + 40 @@ -652,38 +658,5 @@ margin:1px; - - - elevonSlider1 - valueChanged(int) - elevonSliderLabel1 - setNum(int) - - - 124 - 126 - - - 124 - 126 - - - - - elevonSlider2 - valueChanged(int) - elevonSliderLabel2 - setNum(int) - - - 362 - 299 - - - 124 - 126 - - - - + diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 1a464524b..9b613fb5d 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -151,6 +151,7 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwAileron2Label->setText("Aileron 2"); m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); + } else if (frameType == "Aileron Single Servo") { plane->setElementId("aileron-single"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Aileron Single Servo")); @@ -166,6 +167,7 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwAileron2Label->setText("Aileron 2"); m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); + } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { // do nothing for now } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { From 9e93c7ded5c4ab13789cbc93711e0caa6816010f Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Mon, 25 Aug 2014 03:21:20 +1000 Subject: [PATCH 071/203] Rename wizard svg file, avoids confusion. TODO: Other duplicate files like this that are shared with config and wizards --- .../pages/outputcalibrationpage.cpp | 2 +- ...shapes.svg => fixedwing-shapes-wizard.svg} | 8182 ++++++++--------- .../plugins/setupwizard/wizardResources.qrc | 2 +- 3 files changed, 4093 insertions(+), 4093 deletions(-) rename ground/openpilotgcs/src/plugins/setupwizard/resources/{fixedwing-shapes.svg => fixedwing-shapes-wizard.svg} (98%) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 969d88472..066b7f942 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -31,7 +31,7 @@ #include "uavobjectmanager.h" const QString OutputCalibrationPage::MULTI_SVG_FILE = QString(":/setupwizard/resources/multirotor-shapes.svg"); -const QString OutputCalibrationPage::FIXEDWING_SVG_FILE = QString(":/setupwizard/resources/fixedwing-shapes.svg"); +const QString OutputCalibrationPage::FIXEDWING_SVG_FILE = QString(":/setupwizard/resources/fixedwing-shapes-wizard.svg"); OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *parent) : AbstractWizardPage(wizard, parent), ui(new Ui::OutputCalibrationPage), m_vehicleBoundsItem(0), diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes-wizard.svg similarity index 98% rename from ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg rename to ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes-wizard.svg index 07d7fe2d0..5c6ab8e1b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes-wizard.svg @@ -1,4092 +1,4092 @@ - - - -image/svg+xml6 - - - - -4 - - - - -4 - + + +image/svg+xml6 + + + + +4 + + + + +4 + \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index 2603c99a1..56bf63139 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -35,8 +35,8 @@ resources/bttn-servo-standard-up.png resources/wizard.png resources/multirotor-shapes.svg + resources/fixedwing-shapes-wizard.svg - resources/fixedwing-shapes.svg resources/bttn-illustration-down.png resources/bttn-illustration-up.png resources/bttn-save-down.png From 6bcc6f32ed48db619beb5399da5c7dcab0bd3008 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Mon, 25 Aug 2014 03:43:59 +1000 Subject: [PATCH 072/203] Add servos, more informative for end users --- .../config/images/fixedwing-shapes.svg | 1049 ++++++++++------- 1 file changed, 596 insertions(+), 453 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index d808e7b14..7b1c32e7b 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -354,13 +354,13 @@ inkscape:pageopacity="0" inkscape:pageshadow="2" inkscape:window-width="1920" - inkscape:window-height="1017" + inkscape:window-height="1057" id="namedview4099" showgrid="false" - inkscape:zoom="1" - inkscape:cx="400.12565" - inkscape:cy="1481.1007" - inkscape:window-x="-8" + inkscape:zoom="2" + inkscape:cx="413.32337" + inkscape:cy="1763.192" + inkscape:window-x="1912" inkscape:window-y="-8" inkscape:window-maximized="1" inkscape:current-layer="Layer_1" @@ -485,453 +485,6 @@ id="Layer_1_1_" display="none" transform="matrix(0.72518345,0,0,0.84952662,17.091168,368.5798)" /> \ No newline at end of file + style="fill:none;stroke:#414042;stroke-width:0.73697907;stroke-miterlimit:10" /> \ No newline at end of file From 7f0901cdda4b75a3a039ec71ec89a65e77e8c450 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Mon, 25 Aug 2014 06:31:52 +1000 Subject: [PATCH 073/203] Create airspeed page --- .../setupwizard/pages/airspeedpage.cpp | 136 +++++++++++++++ .../plugins/setupwizard/pages/airspeedpage.h | 68 ++++++++ .../plugins/setupwizard/pages/airspeedpage.ui | 164 ++++++++++++++++++ 3 files changed, 368 insertions(+) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.ui diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp new file mode 100644 index 000000000..de8ab0bcd --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -0,0 +1,136 @@ +/** + ****************************************************************************** + * + * @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 "airspeedpage.h" +#include "ui_airspeed.h" +#include "setupwizard.h" + +AirSpeedPage::AirSpeedPage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::AirSpeedPage) +{ + ui->setupUi(this); + QSvgRenderer *renderer = new QSvgRenderer(); + renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); + m_airspeedPic = new QGraphicsSvgItem(); + m_airspeedPic->setSharedRenderer(renderer); + QGraphicsScene *scene = new QGraphicsScene(this); + scene->addItem(m_airspeedPic); + ui->typeGraphicsView->setScene(scene); + + setupAirSpeedPageTypesCombo(); + + // Default to Software Estimation + connect(ui->typeCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateImageAndDescription())); + ui->typeCombo->setCurrentIndex(0); +} + +AirSpeedPage::~AirSpeedPage() +{ + delete ui; +} + +void AirSpeedPage::initializePage() +{ + updateAvailableTypes(); + updateImageAndDescription(); +} + +//TODO +bool AirSpeedPage::validatePage() +{ + SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE)ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); + + getWizard()->setVehicleSubType(type); + return true; +} + +void AirSpeedPage::fitInView() +{ + if (m_airspeedPic) { + ui->typeGraphicsView->setSceneRect(m_airspeedPic->boundingRect()); + ui->typeGraphicsView->fitInView(m_airspeedPic, Qt::KeepAspectRatio); + } +} + +void AirSpeedPage::resizeEvent(QResizeEvent *event) +{ + Q_UNUSED(event); + fitInView(); +} + +void AirSpeedPage::showEvent(QShowEvent *event) +{ + Q_UNUSED(event); + fitInView(); +} + +//TODO +void AirSpeedPage::setupAirSpeedPageTypesCombo() +{ + ui->typeCombo->addItem(tr("Aileron Dual Servos"), SetupWizard::FIXED_WING_DUAL_AILERON); + m_descriptions << tr("This setup expects a traditional airframe using two independent aileron servos on their own channel (not connected by Y adapter) plus an elevator and a rudder. "); + + ui->typeCombo->addItem(tr("Aileron Single Servo"), SetupWizard::FIXED_WING_AILERON); + m_descriptions << tr("This setup expects a traditional airframe using a single alieron servo or two servos connected by a Y adapter plus an elevator and a rudder. "); + + ui->typeCombo->addItem(tr("Elevon"), SetupWizard::FIXED_WING_ELEVON); + m_descriptions << tr("This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet supported. Setup should include only two elevons, and should explicitly not include a rudder."); +} + +void AirSpeedPage::updateAvailableTypes() +{ +} + +//TODO +void AirSpeedPage::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::FIXED_WING_DUAL_AILERON: + elementId = "aileron"; + break; + case SetupWizard::FIXED_WING_AILERON: + elementId = "aileron-single"; + break; + case SetupWizard::FIXED_WING_ELEVON: + elementId = "elevon"; + break; + default: + elementId = ""; + break; + } + m_airspeedPic->setElementId(elementId); + ui->typeGraphicsView->setSceneRect(m_airspeedPic->boundingRect()); + ui->typeGraphicsView->fitInView(m_airspeedPic, Qt::KeepAspectRatio); + + ui->typeDescription->setText(description); + +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h new file mode 100644 index 000000000..757d25661 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h @@ -0,0 +1,68 @@ +/** + ****************************************************************************** + * + * @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 AIRSPEEDPAGE_H +#define AIRSPEEDPAGE_H + +#include +#include +#include + +#include "abstractwizardpage.h" + +namespace Ui { +class AirSpeedPage; +} + +class AirSpeedPage : public AbstractWizardPage { + Q_OBJECT + +public: + explicit AirSpeedPage(SetupWizard *wizard, QWidget *parent = 0); + ~AirSpeedPage(); + + void initializePage(); + bool validatePage(); + + void fitInView(); +protected: + void resizeEvent(QResizeEvent *event); + void showEvent(QShowEvent *event); + +private: + Ui::AirSpeedPage *ui; + void setupAirSpeedPageTypesCombo(); + QGraphicsSvgItem *m_fixedwingPic; + void updateAvailableTypes(); + QList m_descriptions; + +private slots: + void updateImageAndDescription(); + +}; + +#endif // AIRSPEEDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.ui new file mode 100644 index 000000000..824124bf3 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.ui @@ -0,0 +1,164 @@ + + + FixedWingPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + <!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:12pt; font-weight:600;">OpenPilot Airspeed Sensor 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 an airspeed sensor also commonly called a Pitot tube. The OpenPilot Platform supports multiple types of hardware airspeed sensors as well as an advanced software based wind speed estimation algorthym which requires no additional hardware although this is slightly less accurate than using a dedicated hardware sensor. </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 airspeed sensor you wish to use below:</span></p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + 4 + + + + + + + 4 + + + + + + 125 + 36 + + + + + 10 + 50 + false + + + + Airspeed type: + + + + + + + + 125 + 20 + + + + + + + + + + + 0 + 0 + + + + Qt::ScrollBarAlwaysOn + + + Qt::ScrollBarAlwaysOff + + + Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse + + + + + + + + + + 0 + 0 + + + + + 200 + 200 + + + + true + + + QFrame::NoFrame + + + 0 + + + 0 + + + Qt::ScrollBarAlwaysOff + + + Qt::ScrollBarAlwaysOff + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + false + + + + + + + + + + From a2af596b56cac8102651b717ab77ee87dedff698 Mon Sep 17 00:00:00 2001 From: m_thread Date: Mon, 25 Aug 2014 23:45:46 +0200 Subject: [PATCH 074/203] OP-1222 Changed servo calibarion to contain min, max and center on the same page. --- .../pages/airframestabfixedwingpage.cpp | 1 - .../pages/outputcalibrationpage.cpp | 186 +++-- .../setupwizard/pages/outputcalibrationpage.h | 10 +- .../pages/outputcalibrationpage.ui | 707 +++++++++++------- 4 files changed, 571 insertions(+), 333 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.cpp index c2d5eebaf..431e84f40 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.cpp @@ -33,7 +33,6 @@ AirframeStabFixedwingPage::AirframeStabFixedwingPage(SetupWizard *wizard, QWidge ui(new Ui::AirframeStabFixedwingPage) { ui->setupUi(this); - setFinalPage(true); } AirframeStabFixedwingPage::~AirframeStabFixedwingPage() diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 969d88472..5b16e12f4 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -46,6 +46,15 @@ OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *paren m_vehicleScene = new QGraphicsScene(this); ui->vehicleView->setScene(m_vehicleScene); + connect(ui->motorNeutralButton, SIGNAL(toggled(bool)), this, SLOT(on_motorNeutralButton_toggled(bool))); + connect(ui->motorNeutralSlider, SIGNAL(valueChanged(int)), this, SLOT(on_motorNeutralSlider_valueChanged(int))); + + connect(ui->servoButton, SIGNAL(toggled(bool)), this, SLOT(on_servoButton_toggled(bool))); + connect(ui->servoMinAngleSlider, SIGNAL(valueChanged(int)), this, SLOT(on_servoMinAngleSlider_valueChanged(int))); + connect(ui->servoCenterAngleSlider, SIGNAL(valueChanged(int)), this, SLOT(on_servoCenterAngleSlider_valueChanged(int))); + connect(ui->servoMaxAngleSlider, SIGNAL(valueChanged(int)), this, SLOT(on_servoMaxAngleSlider_valueChanged(int))); + + connect(ui->reverseCheckbox, SIGNAL(toggled(bool)), this, SLOT(on_reverseCheckbox_toggled(bool))); } OutputCalibrationPage::~OutputCalibrationPage() @@ -108,17 +117,17 @@ void OutputCalibrationPage::setupVehicle() // The m_wizardIndexes array contains the index of the QStackedWidget // in the page to use for each step. - m_wizardIndexes << 0 << 1 << 1 << 1 << 2 << 3 << 4; + m_wizardIndexes << 0 << 1 << 1 << 1 << 2; // All element ids to load from the svg file and manage. m_vehicleElementIds << "tri" << "tri-frame" << "tri-m1" << "tri-m2" << "tri-m3" << "tri-s1"; // The index of the elementId to highlight ( not dim ) for each step // this is the index in the m_vehicleElementIds - 1. - m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 4 << 4; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4; // The channel number to configure for each step. - m_channelIndex << 0 << 0 << 1 << 2 << 3 << 3 << 3; + m_channelIndex << 0 << 0 << 1 << 2 << 3; setupActuatorMinMaxAndNeutral(0, 2, 3); @@ -174,34 +183,34 @@ void OutputCalibrationPage::setupVehicle() // Fixed Wing case SetupWizard::FIXED_WING_DUAL_AILERON: loadSVGFile(FIXEDWING_SVG_FILE); - m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4; + m_wizardIndexes << 0 << 1 << 2 << 2 << 2 << 2; m_vehicleElementIds << "aileron" << "aileron-frame" << "aileron-motor" << "aileron-ail-left" << "aileron-ail-right" << "aileron-rudder" << "aileron-elevator"; - m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3 << 4 << 4 << 4 << 5 << 5 << 5; - m_channelIndex << 0 << 2 << 0 << 0 << 0 << 1 << 1 << 1 << 3 << 3 << 3 << 4 << 4 << 4; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5; + m_channelIndex << 0 << 2 << 0 << 1 << 3 << 4; - setupActuatorMinMaxAndNeutral(3, 3, 5); + setupActuatorMinMaxAndNeutral(2, 2, 5); getWizard()->setActuatorSettings(m_actuatorSettings); break; case SetupWizard::FIXED_WING_AILERON: loadSVGFile(FIXEDWING_SVG_FILE); - m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4 << 2 << 3 << 4; + m_wizardIndexes << 0 << 1 << 2 << 2 << 2; m_vehicleElementIds << "aileron-single" << "ail2-frame" << "ail2-motor" << "ail2-aileron" << "ail2-rudder" << "ail2-elevator"; - m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3 << 4 << 4 << 4; - m_channelIndex << 0 << 2 << 0 << 0 << 0 << 4 << 4 << 4 << 1 << 1 << 1; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4; + m_channelIndex << 0 << 2 << 0 << 4 << 1; - setupActuatorMinMaxAndNeutral(3, 3, 4); + setupActuatorMinMaxAndNeutral(2, 2, 4); getWizard()->setActuatorSettings(m_actuatorSettings); break; case SetupWizard::FIXED_WING_ELEVON: loadSVGFile(FIXEDWING_SVG_FILE); - m_wizardIndexes << 0 << 1 << 2 << 3 << 4 << 2 << 3 << 4; + m_wizardIndexes << 0 << 1 << 2 << 2; m_vehicleElementIds << "elevon" << "elevon-frame" << "elevon-motor" << "elevon-left" << "elevon-right"; - m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 2 << 2 << 3 << 3 << 3; - m_channelIndex << 0 << 2 << 0 << 0 << 0 << 1 << 1 << 1; + m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3; + m_channelIndex << 0 << 2 << 0 << 1; - setupActuatorMinMaxAndNeutral(3, 3, 3); + setupActuatorMinMaxAndNeutral(2, 2, 3); getWizard()->setActuatorSettings(m_actuatorSettings); break; @@ -283,13 +292,16 @@ void OutputCalibrationPage::setWizardPage() 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); + enableServoSliders(false); + if (ui->reverseCheckbox->isChecked()) { + ui->servoMaxAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMax); + ui->servoCenterAngleSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral); + ui->servoMinAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMin); + } else { + ui->servoMinAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMin); + ui->servoCenterAngleSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral); + ui->servoMaxAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMax); + } } } setupVehicleHighlightedPart(); @@ -360,6 +372,7 @@ void OutputCalibrationPage::enableButtons(bool enable) void OutputCalibrationPage::on_motorNeutralButton_toggled(bool checked) { ui->motorNeutralButton->setText(checked ? tr("Stop") : tr("Start")); + ui->motorNeutralSlider->setEnabled(checked); quint16 channel = getCurrentChannel(); quint16 safeValue = m_actuatorSettings[channel].channelNeutral; onStartButtonToggle(ui->motorNeutralButton, channel, m_actuatorSettings[channel].channelNeutral, safeValue, ui->motorNeutralSlider); @@ -370,6 +383,7 @@ void OutputCalibrationPage::onStartButtonToggle(QAbstractButton *button, quint16 if (button->isChecked()) { if (checkAlarms()) { enableButtons(false); + enableServoSliders(true); m_calibrationUtil->startChannelOutput(channel, safeValue); slider->setValue(value); m_calibrationUtil->setChannelOutputValue(value); @@ -378,11 +392,20 @@ void OutputCalibrationPage::onStartButtonToggle(QAbstractButton *button, quint16 } } else { m_calibrationUtil->stopChannelOutput(); + enableServoSliders(false); enableButtons(true); } debugLogChannelValues(); } +void OutputCalibrationPage::enableServoSliders(bool enabled) +{ + ui->servoCenterAngleSlider->setEnabled(enabled); + ui->servoMinAngleSlider->setEnabled(enabled); + ui->servoMaxAngleSlider->setEnabled(enabled); + ui->reverseCheckbox->setEnabled(!enabled); +} + bool OutputCalibrationPage::checkAlarms() { ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); @@ -434,68 +457,103 @@ void OutputCalibrationPage::on_motorNeutralSlider_valueChanged(int value) } } -void OutputCalibrationPage::on_servoCenterButton_toggled(bool checked) +void OutputCalibrationPage::on_servoButton_toggled(bool checked) { - ui->servoCenterButton->setText(checked ? tr("Stop") : tr("Start")); + ui->servoButton->setText(checked ? tr("Stop") : tr("Start")); quint16 channel = getCurrentChannel(); - quint16 safeValue = m_actuatorSettings[channel].channelNeutral; - onStartButtonToggle(ui->servoCenterButton, channel, safeValue, safeValue, ui->servoCenterSlider); + quint16 safeValue = m_actuatorSettings[channel].channelNeutral; + onStartButtonToggle(ui->servoButton, channel, safeValue, safeValue, ui->servoCenterAngleSlider); } -void OutputCalibrationPage::on_servoCenterSlider_valueChanged(int position) +void OutputCalibrationPage::on_servoCenterAngleSlider_valueChanged(int position) { Q_UNUSED(position); - if (ui->servoCenterButton->isChecked()) { - quint16 value = ui->servoCenterSlider->value(); - m_calibrationUtil->setChannelOutputValue(value); - quint16 channel = getCurrentChannel(); - m_actuatorSettings[channel].channelNeutral = value; + quint16 value = ui->servoCenterAngleSlider->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; + // Adjust min and max + if (ui->reverseCheckbox->isChecked()) { + if (value >= m_actuatorSettings[channel].channelMin) { + ui->servoMinAngleSlider->setValue(value); } - if (value > m_actuatorSettings[channel].channelMax) { - m_actuatorSettings[channel].channelMax = value; + if (value <= m_actuatorSettings[channel].channelMax) { + ui->servoMaxAngleSlider->setValue(value); + } + } else { + if (value <= m_actuatorSettings[channel].channelMin) { + ui->servoMinAngleSlider->setValue(value); + } + if (value >= m_actuatorSettings[channel].channelMax) { + ui->servoMaxAngleSlider->setValue(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); + debugLogChannelValues(); } void OutputCalibrationPage::on_servoMinAngleSlider_valueChanged(int position) { Q_UNUSED(position); - if (ui->servoMinAngleButton->isChecked()) { - quint16 value = ui->servoMinAngleSlider->value(); - m_calibrationUtil->setChannelOutputValue(value); - m_actuatorSettings[getCurrentChannel()].channelMin = value; - debugLogChannelValues(); - } -} + quint16 value = ui->servoMinAngleSlider->value(); + m_calibrationUtil->setChannelOutputValue(value); + m_actuatorSettings[getCurrentChannel()].channelMin = value; -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); + // Adjust neutral and max + if (ui->reverseCheckbox->isChecked()) { + if(value <= m_actuatorSettings[getCurrentChannel()].channelNeutral) { + ui->servoCenterAngleSlider->setValue(value); + } + if(value <= m_actuatorSettings[getCurrentChannel()].channelMax) { + ui->servoMaxAngleSlider->setValue(value); + } + } else { + if(value >= m_actuatorSettings[getCurrentChannel()].channelNeutral) { + ui->servoCenterAngleSlider->setValue(value); + } + if(value >= m_actuatorSettings[getCurrentChannel()].channelMax) { + ui->servoMaxAngleSlider->setValue(value); + } + } + debugLogChannelValues(); } void OutputCalibrationPage::on_servoMaxAngleSlider_valueChanged(int position) { Q_UNUSED(position); - if (ui->servoMaxAngleButton->isChecked()) { - quint16 value = ui->servoMaxAngleSlider->value(); - m_calibrationUtil->setChannelOutputValue(value); - m_actuatorSettings[getCurrentChannel()].channelMax = value; - debugLogChannelValues(); + quint16 value = ui->servoMaxAngleSlider->value(); + m_calibrationUtil->setChannelOutputValue(value); + m_actuatorSettings[getCurrentChannel()].channelMax = value; + + // Adjust neutral and min + if (ui->reverseCheckbox->isChecked()) { + if(value >= m_actuatorSettings[getCurrentChannel()].channelNeutral) { + ui->servoCenterAngleSlider->setValue(value); + } + if(value >= m_actuatorSettings[getCurrentChannel()].channelMin) { + ui->servoMinAngleSlider->setValue(value); + } + } else { + if(value <= m_actuatorSettings[getCurrentChannel()].channelNeutral) { + ui->servoCenterAngleSlider->setValue(value); + } + if(value <= m_actuatorSettings[getCurrentChannel()].channelMin) { + ui->servoMinAngleSlider->setValue(value); + } } + debugLogChannelValues(); +} + +void OutputCalibrationPage::on_reverseCheckbox_toggled(bool checked) +{ + if (m_actuatorSettings[getCurrentChannel()].channelMax > m_actuatorSettings[getCurrentChannel()].channelMin) { + quint16 oldMax = m_actuatorSettings[getCurrentChannel()].channelMax; + m_actuatorSettings[getCurrentChannel()].channelMax = m_actuatorSettings[getCurrentChannel()].channelMin; + m_actuatorSettings[getCurrentChannel()].channelMin = oldMax; + } else if (m_actuatorSettings[getCurrentChannel()].channelMax < m_actuatorSettings[getCurrentChannel()].channelMin) { + quint16 oldMax = m_actuatorSettings[getCurrentChannel()].channelMax; + m_actuatorSettings[getCurrentChannel()].channelMax = m_actuatorSettings[getCurrentChannel()].channelMin; + m_actuatorSettings[getCurrentChannel()].channelMin = oldMax; + } + setWizardPage(); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.h index d851fa639..998bd0cf9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.h @@ -65,14 +65,11 @@ 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_servoButton_toggled(bool checked); + void on_servoCenterAngleSlider_valueChanged(int position); void on_servoMinAngleSlider_valueChanged(int position); - - void on_servoMaxAngleButton_toggled(bool checked); void on_servoMaxAngleSlider_valueChanged(int position); + void on_reverseCheckbox_toggled(bool checked); private: void setupVehicle(); @@ -81,6 +78,7 @@ private: void setupVehicleHighlightedPart(); void setWizardPage(); void enableButtons(bool enable); + void enableServoSliders(bool enabled); void onStartButtonToggle(QAbstractButton *button, quint16 channel, quint16 value, quint16 safeValue, QSlider *slider); bool checkAlarms(); void debugLogChannelValues(); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui index e69c67666..fb56f4fb1 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui @@ -31,10 +31,29 @@ + + + + + 0 + 0 + + + + + 200 + 200 + + + + QFrame::NoFrame + + + - 4 + 2 @@ -133,7 +152,7 @@ p, li { white-space: pre-wrap; } - <html><head/><body><p>This step calibrates<span style=" font-weight:600;"> the center position of the servo</span>. 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> + <html><head/><body><p>This step calibrates<span style=" font-weight:600;"> the minimum, center and maximum angle of the servo</span>. To set the angles for this servo, press the Start button below and slide the slider for the angle to set. The servo will follow the sliders position. <br/>When done press button again to stop.</p><p>Check Reverse to reverse servo action.</p></body></html> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop @@ -144,47 +163,435 @@ p, li { white-space: pre-wrap; } - - - false - - - 600 - - - 2400 - - - 1 - - - 10 - - - 1500 - - - true - + - Qt::Horizontal + Qt::Vertical - - false - - - false - - - QSlider::TicksBelow - - - 40 + + + 20 + 40 + + + + + + + + 6 + + + 6 + + + 0 + + + 0 + + + 0 + + + 0 + + + + + QSlider::groove:horizontal { + border: 1px solid rgb(196, 196, 196); + background: white; + height: 6px; + border-radius: 2px; + margin 10px 10px; +} + +QSlider::add-page:horizontal { + background: #fff; + border: 1px solid #777; + height: 1px; + border-radius: 4px; +} + +QSlider::add-page:horizontal:disabled { + background: #eee; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + +QSlider::sub-page:horizontal { + background: rgb(78, 147, 246); + border: 1px solid #777; + height: 1px; + border-radius: 4px; +} + +QSlider::sub-page:horizontal:disabled { + background: #ccc; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + +QSlider::handle:horizontal { + background: rgb(196, 196, 196); + width: 18px; + height: 28px; + margin: -2px 0; + border-radius: 3px; + border: 1px solid #777; +} + +QSlider::groove:vertical { + border: 1px solid rgb(196, 196, 196); + background: white; + width: 6px; + border-radius: 2px; + margin 0px -10px; + margin-top: 5px; + margin-bottom: 5px; +} + +QSlider::sub-page:vertical { + background: #fff; + border: 1px solid #777; + width: 1px; + border-radius: 4px; +} + +QSlider::sub-page:vertical:disabled { + background: #eee; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + +QSlider::add-page:vertical { + background: rgb(78, 147, 246); + border: 1px solid #777; + width: 1px; + border-radius: 4px; +} + +QSlider::add-page:vertical:disabled { + background: #ccc; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + +QSlider::handle:vertical { + background: rgb(196, 196, 196); + width: 18px; + margin: -6 -6; + border-radius: 3px; + border: 1px solid #777; +} + +QSlider::handle:vertical:hover { + background: qlineargradient(x1:0, y1:0, x2:1, y2:1, stop:0 #fff, stop:1 #ddd); + border: 1px solid #444; + border-radius: 4px; +} + +QSlider::handle:horizontal:hover { + background: qlineargradient(x1:0, y1:0, x2:1, y2:1, stop:0 #fff, stop:1 #ddd); + border: 1px solid #444; + border-radius: 4px; +} + + + 600 + + + 2400 + + + 1500 + + + Qt::Horizontal + + + + + + + QSlider::groove:horizontal { + border: 1px solid rgb(196, 196, 196); + background: white; + height: 6px; + border-radius: 2px; + margin 10px 10px; +} + +QSlider::add-page:horizontal { + background: rgb(78, 147, 246); + border: 1px solid #777; + height: 1px; + border-radius: 4px; +} + +QSlider::add-page:horizontal:disabled { + background: #eee; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + +QSlider::sub-page:horizontal { + background: rgb(78, 147, 246); + border: 1px solid #777; + height: 1px; + border-radius: 4px; +} + +QSlider::sub-page:horizontal:disabled { + background: #eee; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + +QSlider::handle:horizontal { + background: rgb(196, 196, 196); + width: 18px; + height: 28px; + margin: -2px 0; + border-radius: 3px; + border: 1px solid #777; +} + +QSlider::groove:vertical { + border: 1px solid rgb(196, 196, 196); + background: white; + width: 6px; + border-radius: 2px; + margin 0px -10px; + margin-top: 5px; + margin-bottom: 5px; +} + +QSlider::sub-page:vertical { + background: #fff; + border: 1px solid #777; + width: 1px; + border-radius: 4px; +} + +QSlider::sub-page:vertical:disabled { + background: #eee; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + +QSlider::add-page:vertical { + background: rgb(78, 147, 246); + border: 1px solid #777; + width: 1px; + border-radius: 4px; +} + +QSlider::add-page:vertical:disabled { + background: #ccc; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + +QSlider::handle:vertical { + background: rgb(196, 196, 196); + width: 18px; + margin: -6 -6; + border-radius: 3px; + border: 1px solid #777; +} + +QSlider::handle:vertical:hover { + background: qlineargradient(x1:0, y1:0, x2:1, y2:1, stop:0 #fff, stop:1 #ddd); + border: 1px solid #444; + border-radius: 4px; +} + +QSlider::handle:horizontal:hover { + background: qlineargradient(x1:0, y1:0, x2:1, y2:1, stop:0 #fff, stop:1 #ddd); + border: 1px solid #444; + border-radius: 4px; +} + + + 600 + + + 2400 + + + 1500 + + + Qt::Horizontal + + + + + + + QSlider::groove:horizontal { + border: 1px solid rgb(196, 196, 196); + background: white; + height: 6px; + border-radius: 2px; + margin 10px 10px; +} + +QSlider::sub-page:horizontal { + background: #fff; + border: 1px solid #777; + height: 1px; + border-radius: 4px; +} + +QSlider::sub-page:horizontal:disabled { + background: #eee; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + +QSlider::add-page:horizontal { + background: rgb(78, 147, 246); + border: 1px solid #777; + height: 1px; + border-radius: 4px; +} + +QSlider::add-page:horizontal:disabled { + background: #ccc; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + +QSlider::handle:horizontal { + background: rgb(196, 196, 196); + width: 18px; + height: 28px; + margin: -2px 0; + border-radius: 3px; + border: 1px solid #777; +} + +QSlider::groove:vertical { + border: 1px solid rgb(196, 196, 196); + background: white; + width: 6px; + border-radius: 2px; + margin 0px -10px; + margin-top: 5px; + margin-bottom: 5px; +} + +QSlider::sub-page:vertical { + background: #fff; + border: 1px solid #777; + width: 1px; + border-radius: 4px; +} + +QSlider::sub-page:vertical:disabled { + background: #eee; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + +QSlider::add-page:vertical { + background: rgb(78, 147, 246); + border: 1px solid #777; + width: 1px; + border-radius: 4px; +} + +QSlider::add-page:vertical:disabled { + background: #ccc; + border: 1px solid #999; + width: 1px; + border-radius: 4px; +} + +QSlider::handle:vertical { + background: rgb(196, 196, 196); + width: 18px; + margin: -6 -6; + border-radius: 3px; + border: 1px solid #777; +} + +QSlider::handle:vertical:hover { + background: qlineargradient(x1:0, y1:0, x2:1, y2:1, stop:0 #fff, stop:1 #ddd); + border: 1px solid #444; + border-radius: 4px; +} + +QSlider::handle:horizontal:hover { + background: qlineargradient(x1:0, y1:0, x2:1, y2:1, stop:0 #fff, stop:1 #ddd); + border: 1px solid #444; + border-radius: 4px; +} + + + 600 + + + 2400 + + + 1500 + + + Qt::Horizontal + + + false + + + + + + + Reverse + + + + + + + Min + + + + + + + Center + + + + + + + Max + + + + - + Start @@ -198,234 +605,10 @@ p, li { white-space: pre-wrap; } - - - - - - <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 <span style=" font-weight:600;">the minimum angle for the servo</span>, 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> - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - - false - - - 600 - - - 2400 - - - 1 - - - 10 - - - 1500 - - - true - - - Qt::Horizontal - - - false - - - false - - - QSlider::TicksBelow - - - 40 - - - - - - - Start - - - true - - - false - - - - - - - - - - - <html><head/><body><p>To set <span style=" font-weight:600;">the maximum angle for the servo</span>, 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> - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - - false - - - 600 - - - 2400 - - - 1 - - - 10 - - - 1500 - - - true - - - Qt::Horizontal - - - false - - - false - - - QSlider::TicksBelow - - - 40 - - - - - - - Start - - - true - - - false - - - - - - - - - - - - 0 - 0 - - - - - 200 - 200 - - - - QFrame::NoFrame - - - - motorNeutralButton - toggled(bool) - motorNeutralSlider - setEnabled(bool) - - - 147 - 291 - - - 150 - 249 - - - - - servoMinAngleButton - toggled(bool) - servoMinAngleSlider - setEnabled(bool) - - - 147 - 291 - - - 150 - 249 - - - - - servoMaxAngleButton - toggled(bool) - servoMaxAngleSlider - setEnabled(bool) - - - 147 - 291 - - - 150 - 249 - - - - - servoCenterButton - toggled(bool) - servoCenterSlider - setEnabled(bool) - - - 147 - 291 - - - 150 - 249 - - - - + From 73ca58ce0fd5cdecad8b6a8ce01fd868940bf1b4 Mon Sep 17 00:00:00 2001 From: m_thread Date: Tue, 26 Aug 2014 00:02:44 +0200 Subject: [PATCH 075/203] OP-1222 Disabled reverse. --- .../src/plugins/setupwizard/pages/outputcalibrationpage.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 2c35eff2d..a7fadd1f1 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -403,7 +403,8 @@ void OutputCalibrationPage::enableServoSliders(bool enabled) ui->servoCenterAngleSlider->setEnabled(enabled); ui->servoMinAngleSlider->setEnabled(enabled); ui->servoMaxAngleSlider->setEnabled(enabled); - ui->reverseCheckbox->setEnabled(!enabled); + //ui->reverseCheckbox->setEnabled(!enabled); + ui->reverseCheckbox->setEnabled(false); } bool OutputCalibrationPage::checkAlarms() From a9dad6f4dfb798ffa278476a4a4d2a3ec9842d82 Mon Sep 17 00:00:00 2001 From: m_thread Date: Tue, 26 Aug 2014 01:22:35 +0200 Subject: [PATCH 076/203] OP-1222 Added reversed for servos. Beautification of fixed wing page. --- .../setupwizard/pages/fixedwingpage.ui | 18 ++++++--- .../pages/outputcalibrationpage.cpp | 40 ++++++++++++------- 2 files changed, 37 insertions(+), 21 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui index e4bba0fd7..59039632a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui @@ -49,11 +49,11 @@ p, li { white-space: pre-wrap; } - - - 125 - 36 - + + + 0 + 0 + @@ -69,6 +69,12 @@ p, li { white-space: pre-wrap; } + + + 0 + 0 + + 125 @@ -82,7 +88,7 @@ p, li { white-space: pre-wrap; } - + 0 0 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index a7fadd1f1..385e4705b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -45,16 +45,6 @@ OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *paren // move the code that was here to setupVehicle() so we can determine which image to use. m_vehicleScene = new QGraphicsScene(this); ui->vehicleView->setScene(m_vehicleScene); - - connect(ui->motorNeutralButton, SIGNAL(toggled(bool)), this, SLOT(on_motorNeutralButton_toggled(bool))); - connect(ui->motorNeutralSlider, SIGNAL(valueChanged(int)), this, SLOT(on_motorNeutralSlider_valueChanged(int))); - - connect(ui->servoButton, SIGNAL(toggled(bool)), this, SLOT(on_servoButton_toggled(bool))); - connect(ui->servoMinAngleSlider, SIGNAL(valueChanged(int)), this, SLOT(on_servoMinAngleSlider_valueChanged(int))); - connect(ui->servoCenterAngleSlider, SIGNAL(valueChanged(int)), this, SLOT(on_servoCenterAngleSlider_valueChanged(int))); - connect(ui->servoMaxAngleSlider, SIGNAL(valueChanged(int)), this, SLOT(on_servoMaxAngleSlider_valueChanged(int))); - - connect(ui->reverseCheckbox, SIGNAL(toggled(bool)), this, SLOT(on_reverseCheckbox_toggled(bool))); } OutputCalibrationPage::~OutputCalibrationPage() @@ -292,6 +282,12 @@ void OutputCalibrationPage::setWizardPage() if (currentPageIndex == 1) { ui->motorNeutralSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral); } else if (currentPageIndex == 2) { + if (m_actuatorSettings[currentChannel].channelMax < m_actuatorSettings[currentChannel].channelMin && + !ui->reverseCheckbox->isChecked()) { + ui->reverseCheckbox->setChecked(true); + } else { + ui->reverseCheckbox->setChecked(false); + } enableServoSliders(false); if (ui->reverseCheckbox->isChecked()) { ui->servoMaxAngleSlider->setValue(m_actuatorSettings[currentChannel].channelMax); @@ -403,8 +399,7 @@ void OutputCalibrationPage::enableServoSliders(bool enabled) ui->servoCenterAngleSlider->setEnabled(enabled); ui->servoMinAngleSlider->setEnabled(enabled); ui->servoMaxAngleSlider->setEnabled(enabled); - //ui->reverseCheckbox->setEnabled(!enabled); - ui->reverseCheckbox->setEnabled(false); + ui->reverseCheckbox->setEnabled(!enabled); } bool OutputCalibrationPage::checkAlarms() @@ -547,14 +542,29 @@ void OutputCalibrationPage::on_servoMaxAngleSlider_valueChanged(int position) void OutputCalibrationPage::on_reverseCheckbox_toggled(bool checked) { - if (m_actuatorSettings[getCurrentChannel()].channelMax > m_actuatorSettings[getCurrentChannel()].channelMin) { + if (checked && m_actuatorSettings[getCurrentChannel()].channelMax > m_actuatorSettings[getCurrentChannel()].channelMin) { quint16 oldMax = m_actuatorSettings[getCurrentChannel()].channelMax; m_actuatorSettings[getCurrentChannel()].channelMax = m_actuatorSettings[getCurrentChannel()].channelMin; m_actuatorSettings[getCurrentChannel()].channelMin = oldMax; - } else if (m_actuatorSettings[getCurrentChannel()].channelMax < m_actuatorSettings[getCurrentChannel()].channelMin) { + } else if (!checked && m_actuatorSettings[getCurrentChannel()].channelMax < m_actuatorSettings[getCurrentChannel()].channelMin) { quint16 oldMax = m_actuatorSettings[getCurrentChannel()].channelMax; m_actuatorSettings[getCurrentChannel()].channelMax = m_actuatorSettings[getCurrentChannel()].channelMin; m_actuatorSettings[getCurrentChannel()].channelMin = oldMax; } - setWizardPage(); + ui->servoCenterAngleSlider->setInvertedAppearance(checked); + ui->servoCenterAngleSlider->setInvertedControls(checked); + ui->servoMinAngleSlider->setInvertedAppearance(checked); + ui->servoMinAngleSlider->setInvertedControls(checked); + ui->servoMaxAngleSlider->setInvertedAppearance(checked); + ui->servoMaxAngleSlider->setInvertedControls(checked); + + if (ui->reverseCheckbox->isChecked()) { + ui->servoMaxAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelMax); + ui->servoCenterAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelNeutral); + ui->servoMinAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelMin); + } else { + ui->servoMinAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelMin); + ui->servoCenterAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelNeutral); + ui->servoMaxAngleSlider->setValue(m_actuatorSettings[getCurrentChannel()].channelMax); + } } From 934faa5f8a4eb94d75cfe9020603f2c863afd27b Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 26 Aug 2014 12:12:33 +1000 Subject: [PATCH 077/203] Revert adding servos based on Eric's feedback --- .../config/images/fixedwing-shapes.svg | 1413 +---------------- 1 file changed, 10 insertions(+), 1403 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index 7b1c32e7b..48da37c27 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -354,13 +354,13 @@ inkscape:pageopacity="0" inkscape:pageshadow="2" inkscape:window-width="1920" - inkscape:window-height="1057" + inkscape:window-height="1017" id="namedview4099" showgrid="false" - inkscape:zoom="2" + inkscape:zoom="1.4142136" inkscape:cx="413.32337" - inkscape:cy="1763.192" - inkscape:window-x="1912" + inkscape:cy="848.59649" + inkscape:window-x="-8" inkscape:window-y="-8" inkscape:window-maximized="1" inkscape:current-layer="Layer_1" @@ -1170,1256 +1170,7 @@ d="M 231.089,661.657 V 636.359" id="path8516_1_" inkscape:connector-curvature="0" - style="fill:none;stroke:#010101;stroke-width:0.69520003;stroke-linecap:round;stroke-linejoin:round" /> \ No newline at end of file + style="fill:none;stroke:#010101;stroke-width:0.69520003;stroke-linecap:round;stroke-linejoin:round" /> \ No newline at end of file From 221dd1308fa156b352c6805ab387eca5ad5a91de Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 26 Aug 2014 12:13:21 +1000 Subject: [PATCH 078/203] Create new file for the main fixed wing page, on the fixed wing page we need to show the servo types due to the need of knowing how many servos to calibrate --- .../fixedwing-shapes-wizard-no-numbers.svg | 3012 +++++++++++++++++ 1 file changed, 3012 insertions(+) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg new file mode 100644 index 000000000..7b1c32e7b --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg @@ -0,0 +1,3012 @@ + + + +image/svg+xml \ No newline at end of file From a4d2582cec79e835c4550ee12de2138500d2d25c Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 26 Aug 2014 12:44:11 +1000 Subject: [PATCH 079/203] Move Config plugin for fixed wings back to oly Aileron type per Eric --- .../configfixedwingwidget.cpp | 30 +++++-------------- .../config/configvehicletypewidget.cpp | 5 ++-- .../setupwizard/pages/fixedwingpage.cpp | 2 +- .../plugins/setupwizard/wizardResources.qrc | 1 + 4 files changed, 11 insertions(+), 27 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 9b613fb5d..948d99dfa 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -53,11 +53,11 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : populateChannelComboBoxes(); QStringList fixedWingTypes; - fixedWingTypes << "Aileron Dual Servo" << "Aileron Single Servo" << "Elevon"; + fixedWingTypes << "Aileron" << "Elevon"; m_aircraft->fixedWingType->addItems(fixedWingTypes); - // Set default model to "Aileron Dual Servo" - m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Aileron Dual Servo")); + // Set default model to "Aileron" + m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Aileron")); setupUI(m_aircraft->fixedWingType->currentText()); @@ -135,9 +135,9 @@ void ConfigFixedWingWidget::setupUI(QString frameType) qDebug() << "Current Aircraft type: \n" << m_aircraft->fixedWingType->currentText(); - if (frameType == "FixedWing" || frameType == "Aileron Dual Servo") { + if (frameType == "FixedWing" || frameType == "Aileron") { plane->setElementId("aileron"); - setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Aileron Dual Servo")); + setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Aileron")); resetChannelboxesAndSliders(); m_aircraft->fwRudder1ChannelBox->setEnabled(true); @@ -152,22 +152,6 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); - } else if (frameType == "Aileron Single Servo") { - plane->setElementId("aileron-single"); - setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Aileron Single Servo")); - resetChannelboxesAndSliders(); - m_aircraft->fwRudder1ChannelBox->setEnabled(true); - m_aircraft->fwRudder2ChannelBox->setEnabled(true); - m_aircraft->fwElevator1ChannelBox->setEnabled(true); - m_aircraft->fwElevator2ChannelBox->setEnabled(true); - m_aircraft->fwAileron1ChannelBox->setEnabled(true); - m_aircraft->fwAileron2ChannelBox->setEnabled(false); - - m_aircraft->fwAileron1Label->setText("Aileron 1"); - m_aircraft->fwAileron2Label->setText("Aileron 2"); - m_aircraft->fwElevator1Label->setText("Elevator 1"); - m_aircraft->fwElevator2Label->setText("Elevator 2"); - } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { // do nothing for now } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { @@ -218,7 +202,7 @@ void ConfigFixedWingWidget::setupEnabledControls(QString frameType) // enableComboBoxes(this, CHANNELBOXNAME, 3, true); } else if (frameType == "Elevon" || frameType == "Elevon") { enableComboBoxes(this, CHANNELBOXNAME, 3, true); - } else if (frameType == "aileron" || frameType == "Aileron Dual Servo" || frameType == "Aileron Single Servo") { + } else if (frameType == "aileron" || frameType == "Aileron") { enableComboBoxes(this, CHANNELBOXNAME, 4, true); } } @@ -316,7 +300,7 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() QString airframeType; QList motor_servo_List; - if (m_aircraft->fixedWingType->currentText() == "Aileron Dual Servo" || "aileron-single") { + if (m_aircraft->fixedWingType->currentText() == "Aileron") { airframeType = "FixedWing"; setupFrameFixedWing(airframeType); diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 575499753..44b4dcc4a 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -261,9 +261,8 @@ void ConfigVehicleTypeWidget::updateObjectsFromWidgets() int ConfigVehicleTypeWidget::frameCategory(QString frameType) { - if (frameType == "FixedWing" || frameType == "Aileron Dual Servo" || frameType == "Aileron Single Servo" - || frameType == "FixedWingElevon" || frameType == "Elevon" || frameType == "FixedWingVtail" - || frameType == "Vtail") { + if (frameType == "FixedWing" || frameType == "Aileron" || frameType == "FixedWingElevon" + || frameType == "Elevon" || frameType == "FixedWingVtail" || frameType == "Vtail") { return ConfigVehicleTypeWidget::FIXED_WING; } else if (frameType == "Tri" || frameType == "Tricopter Y" || frameType == "QuadX" || frameType == "Quad X" || frameType == "QuadP" || frameType == "Quad +" || frameType == "Hexa" || frameType == "Hexacopter" diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index ab506ccd6..bc8e96d05 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -35,7 +35,7 @@ FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) : { ui->setupUi(this); QSvgRenderer *renderer = new QSvgRenderer(); - renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); + renderer->load(QString(":/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg")); m_fixedwingPic = new QGraphicsSvgItem(); m_fixedwingPic->setSharedRenderer(renderer); QGraphicsScene *scene = new QGraphicsScene(this); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index 56bf63139..850bf1f05 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -36,6 +36,7 @@ resources/wizard.png resources/multirotor-shapes.svg resources/fixedwing-shapes-wizard.svg + resources/fixedwing-shapes-wizard-no-numbers.svg resources/bttn-illustration-down.png resources/bttn-illustration-up.png From 8befdeb9b2d9d9fe20475490cd3f461ffc84d4b0 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 26 Aug 2014 16:16:01 +1000 Subject: [PATCH 080/203] Cleanup the fixed-wing part of the config plugin, I am not sure what happened to this file and I'm not sure I want to know. --- .../src/plugins/config/airframe_fixedwing.ui | 42 ++ .../configfixedwingwidget.cpp | 498 ++++++++---------- .../cfg_vehicletypes/configfixedwingwidget.h | 20 +- 3 files changed, 268 insertions(+), 292 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui index 4786f9e40..01897f547 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui @@ -469,6 +469,12 @@ margin:1px; + + + 70 + 0 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -499,6 +505,12 @@ margin:1px; + + + 70 + 0 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -523,6 +535,12 @@ margin:1px; + + + 70 + 0 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -560,6 +578,12 @@ margin:1px; + + + 70 + 0 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -581,6 +605,12 @@ margin:1px; + + + 70 + 0 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -602,6 +632,12 @@ margin:1px; + + + 70 + 0 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); @@ -623,6 +659,12 @@ margin:1px; + + + 70 + 0 + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 948d99dfa..dae3f20d5 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file configfixedwidget.cpp - * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin @@ -36,40 +36,10 @@ #include #include #include -#include #include #include #include -const QString ConfigFixedWingWidget::CHANNELBOXNAME = QString("fixedWingChannelBox"); - -ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : - VehicleConfig(parent), m_aircraft(new Ui_FixedWingConfigWidget()), - plane(NULL) -{ - m_aircraft->setupUi(this); - - plane = new QGraphicsSvgItem(); - populateChannelComboBoxes(); - - QStringList fixedWingTypes; - fixedWingTypes << "Aileron" << "Elevon"; - m_aircraft->fixedWingType->addItems(fixedWingTypes); - - // Set default model to "Aileron" - m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Aileron")); - - setupUI(m_aircraft->fixedWingType->currentText()); - - connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); - updateEnableControls(); -} - -ConfigFixedWingWidget::~ConfigFixedWingWidget() -{ - delete m_aircraft; -} - QStringList ConfigFixedWingWidget::getChannelDescriptions() { // init a channel_numelem list of channel desc defaults @@ -81,65 +51,72 @@ QStringList ConfigFixedWingWidget::getChannelDescriptions() // get the gui config data GUIConfigDataUnion configData = getConfigData(); - fixedGUISettingsStruct fixed = configData.fixedwing; - if (fixed.FixedWingThrottle > 0 && fixed.FixedWingThrottle <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingThrottle - 1] = QString("WingThrottle"); + if (configData.fixedwing.FixedWingPitch1 > 0) { + channelDesc[configData.fixedwing.FixedWingPitch1 - 1] = QString("FixedWingPitch1"); } - if (fixed.FixedWingPitch1 > 0 && fixed.FixedWingPitch1 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingPitch1 - 1] = QString("FixedWingPitch1"); + if (configData.fixedwing.FixedWingPitch2 > 0) { + channelDesc[configData.fixedwing.FixedWingPitch2 - 1] = QString("FixedWingPitch2"); } - if (fixed.FixedWingPitch2 > 0 && fixed.FixedWingPitch2 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingPitch2 - 1] = QString("FixedWingPitch2"); + if (configData.fixedwing.FixedWingRoll1 > 0) { + channelDesc[configData.fixedwing.FixedWingRoll1 - 1] = QString("FixedWingRoll1"); } - if (fixed.FixedWingRoll1 > 0 && fixed.FixedWingRoll1 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingRoll1 - 1] = QString("FixedWingRoll1"); + if (configData.fixedwing.FixedWingRoll2 > 0) { + channelDesc[configData.fixedwing.FixedWingRoll2 - 1] = QString("FixedWingRoll2"); } - if (fixed.FixedWingRoll2 > 0 && fixed.FixedWingRoll2 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingRoll2 - 1] = QString("FixedWingRoll2"); + if (configData.fixedwing.FixedWingYaw1 > 0) { + channelDesc[configData.fixedwing.FixedWingYaw1 - 1] = QString("FixedWingYaw1"); } - if (fixed.FixedWingYaw1 > 0 && fixed.FixedWingYaw1 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingYaw1 - 1] = QString("FixedWingYaw1"); + if (configData.fixedwing.FixedWingYaw2 > 0) { + channelDesc[configData.fixedwing.FixedWingYaw2 - 1] = QString("FixedWingYaw2"); } - if (fixed.FixedWingYaw2 > 0 && fixed.FixedWingYaw2 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingYaw2 - 1] = QString("FixedWingYaw2"); + if (configData.fixedwing.FixedWingThrottle > 0) { + channelDesc[configData.fixedwing.FixedWingThrottle - 1] = QString("FixedWingThrottle"); } return channelDesc; } -void ConfigFixedWingWidget::resetChannelboxesAndSliders() +ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : + VehicleConfig(parent), m_aircraft(new Ui_FixedWingConfigWidget()) { - m_aircraft->fwRudder1ChannelBox->setEnabled(false); - m_aircraft->fwRudder2ChannelBox->setEnabled(false); - m_aircraft->fwElevator1ChannelBox->setEnabled(false); - m_aircraft->fwElevator2ChannelBox->setEnabled(false); - m_aircraft->fwAileron1ChannelBox->setEnabled(false); - m_aircraft->fwAileron2ChannelBox->setEnabled(false); - m_aircraft->elevonSlider1->setEnabled(false); - m_aircraft->elevonSlider2->setEnabled(false); + m_aircraft->setupUi(this); + + planeimg = new QGraphicsSvgItem(); + + populateChannelComboBoxes(); + + QStringList fixedWingTypes; + fixedWingTypes << "Aileron" << "Elevon" << "Vtail"; + m_aircraft->fixedWingType->addItems(fixedWingTypes); + + // Set default model to "Aileron" + connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); + m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Aileron")); + setupUI(m_aircraft->fixedWingType->currentText()); } +ConfigFixedWingWidget::~ConfigFixedWingWidget() +{ + delete m_aircraft; +} + +/** + Virtual function to setup the UI + */ void ConfigFixedWingWidget::setupUI(QString frameType) { Q_ASSERT(m_aircraft); - Q_ASSERT(plane); - // This had to be moved from ConfigFixedWingWidget() here since m_aircraft->fixedWingType->currentText() - // did not seem to work properly to choose alternate .svg files. - m_aircraft->planeShape->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + m_aircraft->planeShape->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); m_aircraft->planeShape->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); QSvgRenderer *renderer = new QSvgRenderer(); renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); - plane = new QGraphicsSvgItem(); - plane->setSharedRenderer(renderer); - - qDebug() << "Current Aircraft type: \n" << m_aircraft->fixedWingType->currentText(); + planeimg = new QGraphicsSvgItem(); + planeimg->setSharedRenderer(renderer); if (frameType == "FixedWing" || frameType == "Aileron") { - plane->setElementId("aileron"); + planeimg->setElementId("aileron"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Aileron")); - resetChannelboxesAndSliders(); - m_aircraft->fwRudder1ChannelBox->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true); m_aircraft->fwElevator1ChannelBox->setEnabled(true); @@ -152,59 +129,50 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); - } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { - // do nothing for now + m_aircraft->elevonSlider1->setEnabled(false); + m_aircraft->elevonSlider2->setEnabled(false); } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { - plane->setElementId("elevon"); + planeimg->setElementId("elevon"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); - resetChannelboxesAndSliders(); - - m_aircraft->fwElevator1Label->setText("Elevon 1"); - m_aircraft->fwElevator1ChannelBox->setEnabled(true); - - m_aircraft->fwElevator2Label->setText("Elevon 2"); - m_aircraft->fwElevator2ChannelBox->setEnabled(true); - - m_aircraft->fwAileron1Label->setText("Aileron 1"); - m_aircraft->fwAileron2Label->setText("Aileron 2"); + m_aircraft->fwAileron1Label->setText("Elevon 1"); + m_aircraft->fwAileron2Label->setText("Elevon 2"); + m_aircraft->fwElevator1ChannelBox->setEnabled(false); + m_aircraft->fwElevator2ChannelBox->setEnabled(false); + m_aircraft->fwRudder1ChannelBox->setEnabled(true); + m_aircraft->fwRudder2ChannelBox->setEnabled(true); + m_aircraft->fwElevator1Label->setText("Elevator 1"); + m_aircraft->fwElevator2Label->setText("Elevator 2"); m_aircraft->elevonLabel1->setText("Roll"); m_aircraft->elevonLabel2->setText("Pitch"); m_aircraft->elevonSlider1->setEnabled(true); m_aircraft->elevonSlider2->setEnabled(true); - } + } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { + planeimg->setElementId("aileron"); + setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail")); + m_aircraft->fwRudder1ChannelBox->setEnabled(false); + m_aircraft->fwRudder2ChannelBox->setEnabled(false); + m_aircraft->fwElevator1Label->setText("Vtail 1"); + m_aircraft->fwElevator1ChannelBox->setEnabled(true); + + m_aircraft->fwElevator2Label->setText("Vtail 2"); + m_aircraft->fwElevator2ChannelBox->setEnabled(true); + + m_aircraft->fwAileron1Label->setText("Aileron 1"); + m_aircraft->fwAileron2Label->setText("Aileron 2"); + m_aircraft->elevonLabel1->setText("Rudd"); + m_aircraft->elevonLabel2->setText("Pitch"); + + m_aircraft->elevonSlider1->setEnabled(true); + m_aircraft->elevonSlider2->setEnabled(true); + } QGraphicsScene *scene = new QGraphicsScene(); - scene->addItem(plane); - scene->setSceneRect(plane->boundingRect()); + scene->addItem(planeimg); + scene->setSceneRect(planeimg->boundingRect()); m_aircraft->planeShape->setScene(scene); - setupEnabledControls(frameType); - // Draw the appropriate airframe - updateAirframe(frameType); -} - -void ConfigFixedWingWidget::setupEnabledControls(QString frameType) -{ - - // disable all motor channel boxes - for (int i = 1; i <= 8; i++) { - // do it manually so we can turn off any error decorations - QComboBox *combobox = this->findChild("fixedWingChannelBox" + QString::number(i)); - if (combobox) { - combobox->setEnabled(false); - combobox->setItemData(0, 0, Qt::DecorationRole); - } - } - - if (frameType == "Vtail" || frameType == "vtail") { - // enableComboBoxes(this, CHANNELBOXNAME, 3, true); - } else if (frameType == "Elevon" || frameType == "Elevon") { - enableComboBoxes(this, CHANNELBOXNAME, 3, true); - } else if (frameType == "aileron" || frameType == "Aileron") { - enableComboBoxes(this, CHANNELBOXNAME, 4, true); - } } void ConfigFixedWingWidget::registerWidgets(ConfigTaskWidget &parent) @@ -268,11 +236,13 @@ void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType) setComboCurrentIndex(m_aircraft->fwAileron2ChannelBox, fixed.FixedWingRoll2); setComboCurrentIndex(m_aircraft->fwElevator1ChannelBox, fixed.FixedWingPitch1); setComboCurrentIndex(m_aircraft->fwElevator2ChannelBox, fixed.FixedWingPitch2); + setComboCurrentIndex(m_aircraft->fwRudder1ChannelBox, fixed.FixedWingYaw1); + setComboCurrentIndex(m_aircraft->fwRudder2ChannelBox, fixed.FixedWingYaw2); if (frameType == "FixedWingElevon") { // If the airframe is elevon, restore the slider setting // Find the channel number for Elevon1 (FixedWingRoll1) - int channel = m_aircraft->fwElevator1ChannelBox->currentIndex() - 1; + int channel = m_aircraft->fwAileron1ChannelBox->currentIndex() - 1; if (channel > -1) { // If for some reason the actuators were incoherent, we might fail here, hence the check. m_aircraft->elevonSlider1->setValue( @@ -280,114 +250,49 @@ void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType) m_aircraft->elevonSlider2->setValue( getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH) * 100); } + } else if (frameType == "FixedWingVtail") { + int channel = m_aircraft->fwElevator1ChannelBox->currentIndex() - 1; + if (channel > -1) { + // If for some reason the actuators were incoherent, we might fail here, hence the check. + m_aircraft->elevonSlider1->setValue( + getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW) * 100); + m_aircraft->elevonSlider2->setValue( + getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH) * 100); + } } - - updateAirframe(frameType); } /** - Helper function to update the UI widget objects + Virtual function to update the UI widget objects */ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() { + QString airframeType = "FixedWing"; + + // Save the curve (common to all Fixed wing frames) UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(mixer); - // Curve is also common to all quads: - setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->fixedWingThrottle->getCurve()); - - QString airframeType; - QList motor_servo_List; - - if (m_aircraft->fixedWingType->currentText() == "Aileron") { - airframeType = "FixedWing"; - setupFrameFixedWing(airframeType); - - motor_servo_List << "FixedWingThrottle" << "FixedWingPitch1" << "FixedWingPitch2" << "FixedWingRoll1" << "FixedWingRoll2" << "FixedWingYaw1" << "FixedWingYaw2"; - setupMotors(motor_servo_List); - - GUIConfigDataUnion config = getConfigData(); - setConfigData(config); - - m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); - - } - else if (m_aircraft->fixedWingType->currentText() == "elevon") { - airframeType = "FixedWingElevon"; - setupFrameElevon(airframeType); - - motor_servo_List << "FixedWingThrottle" << "FixedWingRoll1" << "FixedWingRoll2"; - setupMotors(motor_servo_List); - - GUIConfigDataUnion config = getConfigData(); - setConfigData(config); - - // Elevon Layout: - // pitch roll yaw - double mixerMatrix[8][3] = { - { 0, 0, 0 }, - { 1, -1, 0 }, - { -1, 1, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 } - }; - setupFixedWingElevonMixer(mixerMatrix); - - m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); - - } - // Remove Feed Forward, it is pointless on a plane: setMixerValue(mixer, "FeedForward", 0.0); - return airframeType; -} + // Set the throttle curve + setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->fixedWingThrottle->getCurve()); -void ConfigFixedWingWidget::setupMotors(QList motorList) -{ - QList mmList; - mmList << m_aircraft->fwEngineChannelBox << m_aircraft->fwAileron1ChannelBox - << m_aircraft->fwAileron2ChannelBox << m_aircraft->fwElevator1ChannelBox - << m_aircraft->fwElevator2ChannelBox << m_aircraft->fwRudder1ChannelBox - << m_aircraft->fwRudder2ChannelBox; - - GUIConfigDataUnion configData = getConfigData(); - resetActuators(&configData); - - foreach(QString motor, motorList) { - int index = mmList.takeFirst()->currentIndex(); - - if (motor == QString("FixedWingThrottle")) { - configData.fixedwing.FixedWingThrottle = index; - } else if (motor == QString("FixedWingPitch1")) { - configData.fixedwing.FixedWingPitch1 = index; - } else if (motor == QString("FixedWingPitch2")) { - configData.fixedwing.FixedWingPitch2 = index; - } else if (motor == QString("FixedWingRoll1")) { - configData.fixedwing.FixedWingRoll1 = index; - } else if (motor == QString("FixedWingRoll2")) { - configData.fixedwing.FixedWingRoll2 = index; - } else if (motor == QString("FixedWingYaw1")) { - configData.fixedwing.FixedWingYaw1 = index; - } else if (motor == QString("FixedWingYaw2")) { - configData.fixedwing.FixedWingYaw1 = index; - } + // All airframe types must start with "FixedWing" + if (m_aircraft->fixedWingType->currentText() == "Aileron") { + airframeType = "FixedWing"; + setupFrameFixedWing(airframeType); + } else if (m_aircraft->fixedWingType->currentText() == "Elevon") { + airframeType = "FixedWingElevon"; + setupFrameElevon(airframeType); + } else { // "Vtail" + airframeType = "FixedWingVtail"; + setupFrameVtail(airframeType); } - setConfigData(configData); -} -void ConfigFixedWingWidget::updateAirframe(QString frameType) -{ - qDebug() << "ConfigFixedWingWidget::updateAirframe - frame type" << frameType; - - // this is not doing anything right now - - m_aircraft->planeShape->setSceneRect(plane->boundingRect()); - m_aircraft->planeShape->fitInView(plane, Qt::KeepAspectRatio); + return airframeType; } /** @@ -414,7 +319,6 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType) config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex(); config.fixedwing.FixedWingYaw1 = m_aircraft->fwRudder1ChannelBox->currentIndex(); - config.fixedwing.FixedWingYaw2 = m_aircraft->fwRudder2ChannelBox->currentIndex(); config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex(); setConfigData(config); @@ -480,8 +384,78 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) GUIConfigDataUnion config = getConfigData(); resetActuators(&config); + config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); + config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex(); + config.fixedwing.FixedWingYaw1 = m_aircraft->fwRudder1ChannelBox->currentIndex(); + config.fixedwing.FixedWingYaw2 = m_aircraft->fwRudder2ChannelBox->currentIndex(); + config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex(); + + setConfigData(config); + + UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + resetMotorAndServoMixers(mixer); + + // Save the curve: + // ... and compute the matrix: + // In order to make code a bit nicer, we assume: + // - Channel dropdowns start with 'None', then 0 to 7 + + // 1. Assign the servo/motor/none for each channel + + double value; + + // motor + int channel = m_aircraft->fwEngineChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); + + // rudders + channel = m_aircraft->fwRudder1ChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + + channel = m_aircraft->fwRudder2ChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127); + + // ailerons + channel = m_aircraft->fwAileron1ChannelBox->currentIndex() - 1; + if (channel > -1) { + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + value = (double)(m_aircraft->elevonSlider2->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + value = (double)(m_aircraft->elevonSlider1->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, value); + + channel = m_aircraft->fwAileron2ChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + value = (double)(m_aircraft->elevonSlider2->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + value = (double)(m_aircraft->elevonSlider1->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -value); + } + + m_aircraft->fwStatusLabel->setText("Mixer generated"); + return true; +} + +/** + Setup VTail + */ +bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType) +{ + // Check coherence: + // Show any config errors in GUI + if (throwConfigError(airframeType)) { + return false; + } + + GUIConfigDataUnion config = getConfigData(); + resetActuators(&config); + config.fixedwing.FixedWingPitch1 = m_aircraft->fwElevator1ChannelBox->currentIndex(); - config.fixedwing.FixedWingPitch2 = m_aircraft->fwElevator2ChannelBox->currentIndex(); + config.fixedwing.FixedWingPitch2 = m_aircraft->fwElevator2ChannelBox->currentIndex(); config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex(); config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex(); @@ -504,76 +478,54 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR); setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); + // rudders + channel = m_aircraft->fwRudder1ChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + + channel = m_aircraft->fwRudder2ChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127); + // ailerons channel = m_aircraft->fwAileron1ChannelBox->currentIndex() - 1; if (channel > -1) { setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127); channel = m_aircraft->fwAileron2ChannelBox->currentIndex() - 1; setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -127); } - // elevon + // vtail channel = m_aircraft->fwElevator1ChannelBox->currentIndex() - 1; if (channel > -1) { setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, 127); + double value = (double)(m_aircraft->elevonSlider2->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + value = (double)(m_aircraft->elevonSlider1->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, value); channel = m_aircraft->fwElevator2ChannelBox->currentIndex() - 1; setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, -127); + value = (double)(m_aircraft->elevonSlider2->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + value = (double)(m_aircraft->elevonSlider1->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -value); } m_aircraft->fwStatusLabel->setText("Mixer generated"); return true; - - } -/** - Helper function: setupElevonServo - */ -void ConfigFixedWingWidget::setupElevonServo(int channel, double pitch, double roll) +void ConfigFixedWingWidget::enableControls(bool enable) { - UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + ConfigTaskWidget::enableControls(enable); - Q_ASSERT(mixer); - - setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, roll * 127); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, pitch * 127); -} - -/** - This function sets up the elevon fixed wing mixer values. - */ -bool ConfigFixedWingWidget::setupFixedWingElevonMixer(double mixerFactors[8][3]){ - UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - - Q_ASSERT(mixer); - resetMotorAndServoMixers(mixer); - - // and enable only the relevant channels: - double pFactor = (double)m_aircraft->elevonSlider1->value() / 100.0; - double rFactor = (double)m_aircraft->elevonSlider2->value() / 100.0; - - QList mmList; - mmList << m_aircraft->fwEngineChannelBox << m_aircraft->fwAileron1ChannelBox - << m_aircraft->fwAileron2ChannelBox << m_aircraft->fwElevator1ChannelBox - << m_aircraft->fwElevator2ChannelBox; - - for (int i = 0; i < 8; i++) { - if (mmList.at(i)->isEnabled()) { - int channel = mmList.at(i)->currentIndex() - 1; - if (channel > -1) { - setupElevonServo(channel, mixerFactors[i][0] * pFactor, rFactor * mixerFactors[i][1]); - } - } + if (enable) { + setupUI(m_aircraft->fixedWingType->currentText()); } - return true; } /** @@ -616,7 +568,27 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) m_aircraft->fwRudder1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } } else if (airframeType == "FixedWingElevon") { -/* + if (m_aircraft->fwEngineChannelBox->currentText() == "None") { + m_aircraft->fwEngineChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes + error = true; + } else { + m_aircraft->fwEngineChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + } + + if (m_aircraft->fwAileron1ChannelBox->currentText() == "None") { + m_aircraft->fwAileron1ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes + error = true; + } else { + m_aircraft->fwAileron1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + } + + if (m_aircraft->fwAileron2ChannelBox->currentText() == "None") { + m_aircraft->fwAileron2ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes + error = true; + } else { + m_aircraft->fwAileron2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + } + } else if (airframeType == "FixedWingVtail") { if (m_aircraft->fwEngineChannelBox->currentText() == "None") { m_aircraft->fwEngineChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes error = true; @@ -635,9 +607,8 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) m_aircraft->fwElevator2ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes error = true; } else { - m_aircraft->fwElevator2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + m_aircraft->fwElevator2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } -*/ } if (error) { @@ -646,30 +617,3 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) return error; } - -void ConfigFixedWingWidget::showEvent(QShowEvent *event) -{ - Q_UNUSED(event) - Q_ASSERT(plane); - m_aircraft->planeShape->fitInView(plane, Qt::KeepAspectRatio); -} - -/** - Resize the GUI contents when the user changes the window size - */ -void ConfigFixedWingWidget::resizeEvent(QResizeEvent *event) -{ - Q_UNUSED(event); - Q_ASSERT(plane); - m_aircraft->planeShape->fitInView(plane, Qt::KeepAspectRatio); -} - -void ConfigFixedWingWidget::enableControls(bool enable) -{ - ConfigTaskWidget::enableControls(enable); - - if (enable) { - setupEnabledControls(m_aircraft->fixedWingType->currentText()); - } -} - diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index 295be3b4c..f749d4ae0 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -44,7 +44,6 @@ class ConfigFixedWingWidget : public VehicleConfig { Q_OBJECT public: - static const QString CHANNELBOXNAME; static QStringList getChannelDescriptions(); ConfigFixedWingWidget(QWidget *parent = 0); @@ -53,29 +52,20 @@ public: virtual void refreshWidgetsValues(QString frameType); virtual QString updateConfigObjectsFromWidgets(); - void resetChannelboxesAndSliders(); -protected: - void showEvent(QShowEvent *event); - void resizeEvent(QResizeEvent *event); - void enableControls(bool enable); - private: Ui_FixedWingConfigWidget *m_aircraft; - QGraphicsSvgItem *plane; + QGraphicsSvgItem *planeimg; virtual void registerWidgets(ConfigTaskWidget &parent); virtual void resetActuators(GUIConfigDataUnion *configData); bool setupFrameFixedWing(QString airframeType); - bool setupFrameVtail(QString airframeType); bool setupFrameElevon(QString airframeType); - bool setupFixedWingMixer(double mixerFactors[8][3]); - bool setupFixedWingElevonMixer(double mixerFactors[8][3]); - void setupMotors(QList motorList); - void setupElevonServo(int channel, double roll, double pitch); + bool setupFrameVtail(QString airframeType); + +protected: + void enableControls(bool enable); - void updateAirframe(QString multiRotorType); - void setupEnabledControls(QString airframeType); private slots: virtual void setupUI(QString airframeType); virtual bool throwConfigError(QString airframeType); From 6ea2fc67dbade5f197b752f9669fcf7af713a0db Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 26 Aug 2014 16:46:52 +1000 Subject: [PATCH 081/203] When qcombo disabled, change index to None, cosmetic, was never used in mixer but could confuse users, per Eric's suggestion. Reenabled v-tail --- .../config/cfg_vehicletypes/configfixedwingwidget.cpp | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index dae3f20d5..28377d0d1 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -107,7 +107,7 @@ void ConfigFixedWingWidget::setupUI(QString frameType) { Q_ASSERT(m_aircraft); - m_aircraft->planeShape->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + m_aircraft->planeShape->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); m_aircraft->planeShape->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); QSvgRenderer *renderer = new QSvgRenderer(); renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); @@ -137,7 +137,9 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwAileron1Label->setText("Elevon 1"); m_aircraft->fwAileron2Label->setText("Elevon 2"); m_aircraft->fwElevator1ChannelBox->setEnabled(false); + m_aircraft->fwElevator1ChannelBox->setCurrentIndex(0); m_aircraft->fwElevator2ChannelBox->setEnabled(false); + m_aircraft->fwElevator2ChannelBox->setCurrentIndex(0); m_aircraft->fwRudder1ChannelBox->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true); @@ -149,11 +151,12 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->elevonSlider1->setEnabled(true); m_aircraft->elevonSlider2->setEnabled(true); } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { - planeimg->setElementId("aileron"); + planeimg->setElementId("vtail"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail")); m_aircraft->fwRudder1ChannelBox->setEnabled(false); + m_aircraft->fwRudder1ChannelBox->setCurrentIndex(0); m_aircraft->fwRudder2ChannelBox->setEnabled(false); - + m_aircraft->fwRudder2ChannelBox->setCurrentIndex(0); m_aircraft->fwElevator1Label->setText("Vtail 1"); m_aircraft->fwElevator1ChannelBox->setEnabled(true); From 9a59cf347e31f848c84cdd58a12b0eb6408acd5b Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 26 Aug 2014 18:20:56 +1000 Subject: [PATCH 082/203] Create image for vtail in svg --- .../config/images/fixedwing-shapes.svg | 977 +++++++++++++++++- 1 file changed, 973 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index 48da37c27..6f263a812 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -344,7 +344,95 @@ id="stop3445" /> \ No newline at end of file + style="fill:none;stroke:#010101;stroke-width:0.69520003;stroke-linecap:round;stroke-linejoin:round" /> \ No newline at end of file From 71a672674987f2f886f3007961d8e0dbc60dd4b2 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 26 Aug 2014 19:25:06 +1000 Subject: [PATCH 083/203] This file looked fine in inkscape but rendered with a missing gradient in the elevon artwork, a long battle with inkscape and it now renders correctly again --- .../config/images/fixedwing-shapes.svg | 943 +++++++++--------- 1 file changed, 493 insertions(+), 450 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index 6f263a812..b9c6266b3 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -432,7 +432,49 @@ id="stop3643-7-5-0-5-2" /> \ No newline at end of file + d="M 231.089,661.657 V 636.359" /> \ No newline at end of file From a7ad51d335d659e84b7bdfce1bcb8d8153883035 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 26 Aug 2014 19:44:31 +1000 Subject: [PATCH 084/203] Minor UI improvment with the sliders --- .../openpilotgcs/src/plugins/config/airframe_fixedwing.ui | 8 ++++---- .../config/cfg_vehicletypes/configfixedwingwidget.cpp | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui index 01897f547..3732c7931 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui @@ -190,7 +190,7 @@ - 40 + 50 0 @@ -222,7 +222,7 @@ margin:1px; - 40 + 50 0 @@ -264,7 +264,7 @@ margin:1px; - 40 + 50 0 @@ -290,7 +290,7 @@ margin:1px; - 40 + 50 0 diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 28377d0d1..31bee79b6 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -165,7 +165,7 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwAileron1Label->setText("Aileron 1"); m_aircraft->fwAileron2Label->setText("Aileron 2"); - m_aircraft->elevonLabel1->setText("Rudd"); + m_aircraft->elevonLabel1->setText("Rudder"); m_aircraft->elevonLabel2->setText("Pitch"); m_aircraft->elevonSlider1->setEnabled(true); From b31ee46724d0016bf9c54f494438d0380d23510b Mon Sep 17 00:00:00 2001 From: m_thread Date: Tue, 26 Aug 2014 22:34:58 +0200 Subject: [PATCH 085/203] OP-1222 Uncrustify --- .../configfixedwingwidget.cpp | 75 +++++++++---------- .../cfg_vehicletypes/configfixedwingwidget.h | 4 +- .../configmultirotorwidget.cpp | 6 +- .../config/configvehicletypewidget.cpp | 2 +- .../setupwizard/outputcalibrationutil.cpp | 10 +-- .../setupwizard/pages/airspeedpage.cpp | 10 +-- .../plugins/setupwizard/pages/airspeedpage.h | 1 - .../setupwizard/pages/fixedwingpage.cpp | 4 +- .../plugins/setupwizard/pages/fixedwingpage.h | 1 - .../pages/outputcalibrationpage.cpp | 28 +++---- .../plugins/setupwizard/pages/vehiclepage.cpp | 4 +- .../src/plugins/setupwizard/setupwizard.cpp | 7 +- .../vehicleconfigurationhelper.cpp | 54 ++++++------- .../setupwizard/vehicleconfigurationsource.h | 4 +- 14 files changed, 99 insertions(+), 111 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 948d99dfa..43291e243 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -124,8 +124,8 @@ void ConfigFixedWingWidget::setupUI(QString frameType) Q_ASSERT(m_aircraft); Q_ASSERT(plane); - // This had to be moved from ConfigFixedWingWidget() here since m_aircraft->fixedWingType->currentText() - // did not seem to work properly to choose alternate .svg files. + // This had to be moved from ConfigFixedWingWidget() here since m_aircraft->fixedWingType->currentText() + // did not seem to work properly to choose alternate .svg files. m_aircraft->planeShape->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); m_aircraft->planeShape->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); QSvgRenderer *renderer = new QSvgRenderer(); @@ -151,9 +151,8 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwAileron2Label->setText("Aileron 2"); m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); - } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { - // do nothing for now + // do nothing for now } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { plane->setElementId("elevon"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); @@ -187,7 +186,6 @@ void ConfigFixedWingWidget::setupUI(QString frameType) void ConfigFixedWingWidget::setupEnabledControls(QString frameType) { - // disable all motor channel boxes for (int i = 1; i <= 8; i++) { // do it manually so we can turn off any error decorations @@ -204,7 +202,7 @@ void ConfigFixedWingWidget::setupEnabledControls(QString frameType) enableComboBoxes(this, CHANNELBOXNAME, 3, true); } else if (frameType == "aileron" || frameType == "Aileron") { enableComboBoxes(this, CHANNELBOXNAME, 4, true); - } + } } void ConfigFixedWingWidget::registerWidgets(ConfigTaskWidget &parent) @@ -306,41 +304,38 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() motor_servo_List << "FixedWingThrottle" << "FixedWingPitch1" << "FixedWingPitch2" << "FixedWingRoll1" << "FixedWingRoll2" << "FixedWingYaw1" << "FixedWingYaw2"; setupMotors(motor_servo_List); - - GUIConfigDataUnion config = getConfigData(); - setConfigData(config); - m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); + GUIConfigDataUnion config = getConfigData(); + setConfigData(config); - } - else if (m_aircraft->fixedWingType->currentText() == "elevon") { + m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); + } else if (m_aircraft->fixedWingType->currentText() == "elevon") { airframeType = "FixedWingElevon"; setupFrameElevon(airframeType); motor_servo_List << "FixedWingThrottle" << "FixedWingRoll1" << "FixedWingRoll2"; setupMotors(motor_servo_List); - - GUIConfigDataUnion config = getConfigData(); - setConfigData(config); + + GUIConfigDataUnion config = getConfigData(); + setConfigData(config); // Elevon Layout: // pitch roll yaw double mixerMatrix[8][3] = { - { 0, 0, 0 }, - { 1, -1, 0 }, - { -1, 1, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 } + { 0, 0, 0 }, + { 1, -1, 0 }, + { -1, 1, 0 }, + { 0, 0, 0 }, + { 0, 0, 0 }, + { 0, 0, 0 }, + { 0, 0, 0 }, + { 0, 0, 0 } }; - setupFixedWingElevonMixer(mixerMatrix); - - m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); + setupFixedWingElevonMixer(mixerMatrix); + m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); } - + // Remove Feed Forward, it is pointless on a plane: setMixerValue(mixer, "FeedForward", 0.0); @@ -383,8 +378,8 @@ void ConfigFixedWingWidget::setupMotors(QList motorList) void ConfigFixedWingWidget::updateAirframe(QString frameType) { qDebug() << "ConfigFixedWingWidget::updateAirframe - frame type" << frameType; - - // this is not doing anything right now + + // this is not doing anything right now m_aircraft->planeShape->setSceneRect(plane->boundingRect()); m_aircraft->planeShape->fitInView(plane, Qt::KeepAspectRatio); @@ -481,7 +476,7 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) resetActuators(&config); config.fixedwing.FixedWingPitch1 = m_aircraft->fwElevator1ChannelBox->currentIndex(); - config.fixedwing.FixedWingPitch2 = m_aircraft->fwElevator2ChannelBox->currentIndex(); + config.fixedwing.FixedWingPitch2 = m_aircraft->fwElevator2ChannelBox->currentIndex(); config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex(); config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex(); @@ -508,11 +503,11 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) channel = m_aircraft->fwAileron1ChannelBox->currentIndex() - 1; if (channel > -1) { setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127); channel = m_aircraft->fwAileron2ChannelBox->currentIndex() - 1; setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -127); } // elevon @@ -528,8 +523,6 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) m_aircraft->fwStatusLabel->setText("Mixer generated"); return true; - - } /** @@ -549,8 +542,9 @@ void ConfigFixedWingWidget::setupElevonServo(int channel, double pitch, double r /** This function sets up the elevon fixed wing mixer values. - */ -bool ConfigFixedWingWidget::setupFixedWingElevonMixer(double mixerFactors[8][3]){ + */ +bool ConfigFixedWingWidget::setupFixedWingElevonMixer(double mixerFactors[8][3]) +{ UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(mixer); @@ -563,13 +557,13 @@ bool ConfigFixedWingWidget::setupFixedWingElevonMixer(double mixerFactors[8][3]) QList mmList; mmList << m_aircraft->fwEngineChannelBox << m_aircraft->fwAileron1ChannelBox << m_aircraft->fwAileron2ChannelBox << m_aircraft->fwElevator1ChannelBox - << m_aircraft->fwElevator2ChannelBox; + << m_aircraft->fwElevator2ChannelBox; for (int i = 0; i < 8; i++) { if (mmList.at(i)->isEnabled()) { int channel = mmList.at(i)->currentIndex() - 1; if (channel > -1) { - setupElevonServo(channel, mixerFactors[i][0] * pFactor, rFactor * mixerFactors[i][1]); + setupElevonServo(channel, mixerFactors[i][0] * pFactor, rFactor * mixerFactors[i][1]); } } } @@ -635,9 +629,9 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) m_aircraft->fwElevator2ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes error = true; } else { - m_aircraft->fwElevator2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + m_aircraft->fwElevator2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } -*/ + */ } if (error) { @@ -672,4 +666,3 @@ void ConfigFixedWingWidget::enableControls(bool enable) setupEnabledControls(m_aircraft->fixedWingType->currentText()); } } - diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index 295be3b4c..9fd56f8aa 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -54,8 +54,8 @@ public: virtual QString updateConfigObjectsFromWidgets(); void resetChannelboxesAndSliders(); -protected: - void showEvent(QShowEvent *event); +protected: + void showEvent(QShowEvent *event); void resizeEvent(QResizeEvent *event); void enableControls(bool enable); diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index 8216ca7d3..42b06f4d0 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -481,11 +481,11 @@ void ConfigMultiRotorWidget::refreshWidgetsValues(QString frameType) // get motor 2 value for Yaw and Roll channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW); setYawMixLevel(qRound(value / 1.27)); - channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; - value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); + channel = m_aircraft->multiMotorChannelBox2->currentIndex() - 1; + value = getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL); m_aircraft->mrRollMixLevel->setValue(-qRound(value / 1.27)); } } else if (frameType == "HexaCoax") { diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 44b4dcc4a..e113a921c 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -74,7 +74,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions() channelDesc = ConfigFixedWingWidget::getChannelDescriptions(); break; case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL: - // do nothing for vtail support for the time being. + // do nothing for vtail support for the time being. // channelDesc = ConfigFixedWingWidget::getChannelDescriptions(); break; case SystemSettings::AIRFRAMETYPE_HELICP: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.cpp b/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.cpp index 9cbf911fb..a4cee9d88 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/outputcalibrationutil.cpp @@ -52,7 +52,7 @@ void OutputCalibrationUtil::startChannelOutput(quint16 channel, quint16 safeValu m_outputChannel = channel; m_safeValue = safeValue; - qDebug() << "Starting output for channel " << m_outputChannel+1 << "..."; + qDebug() << "Starting output for channel " << m_outputChannel + 1 << "..."; ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager); Q_ASSERT(actuatorCommand); @@ -74,17 +74,17 @@ void OutputCalibrationUtil::startChannelOutput(quint16 channel, quint16 safeValu actuatorCommand->setMetadata(metaData); actuatorCommand->updated(); - qDebug() << "Output for channel " << m_outputChannel+1 << " started."; + qDebug() << "Output for channel " << m_outputChannel + 1 << " started."; } } void OutputCalibrationUtil::stopChannelOutput() { if (m_outputChannel >= 0) { - qDebug() << "Stopping output for channel " << m_outputChannel+1 << "..."; + qDebug() << "Stopping output for channel " << m_outputChannel + 1 << "..."; // Stop output... setChannelOutputValue(m_safeValue); - qDebug() << "Settings output for channel " << m_outputChannel+1 << " to " << m_safeValue; + qDebug() << "Settings output for channel " << m_outputChannel + 1 << " to " << m_safeValue; // Restore metadata to what it was before ActuatorCommand *actuatorCommand = ActuatorCommand::GetInstance(m_uavObjectManager); @@ -93,7 +93,7 @@ void OutputCalibrationUtil::stopChannelOutput() actuatorCommand->setMetadata(m_savedActuatorCommandMetadata); actuatorCommand->updated(); - qDebug() << "Output for channel " << m_outputChannel+1 << " stopped."; + qDebug() << "Output for channel " << m_outputChannel + 1 << " stopped."; m_outputChannel = -1; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index de8ab0bcd..3c7834e2d 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -60,7 +60,7 @@ void AirSpeedPage::initializePage() updateImageAndDescription(); } -//TODO +// TODO bool AirSpeedPage::validatePage() { SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE)ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); @@ -89,7 +89,7 @@ void AirSpeedPage::showEvent(QShowEvent *event) fitInView(); } -//TODO +// TODO void AirSpeedPage::setupAirSpeedPageTypesCombo() { ui->typeCombo->addItem(tr("Aileron Dual Servos"), SetupWizard::FIXED_WING_DUAL_AILERON); @@ -103,10 +103,9 @@ void AirSpeedPage::setupAirSpeedPageTypesCombo() } void AirSpeedPage::updateAvailableTypes() -{ -} +{} -//TODO +// TODO void AirSpeedPage::updateImageAndDescription() { SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE)ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); @@ -132,5 +131,4 @@ void AirSpeedPage::updateImageAndDescription() ui->typeGraphicsView->fitInView(m_airspeedPic, Qt::KeepAspectRatio); ui->typeDescription->setText(description); - } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h index 757d25661..0e3940c67 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h @@ -62,7 +62,6 @@ private: private slots: void updateImageAndDescription(); - }; #endif // AIRSPEEDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index bc8e96d05..3574887d8 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -101,8 +101,7 @@ void FixedWingPage::setupFixedWingTypesCombo() } void FixedWingPage::updateAvailableTypes() -{ -} +{} void FixedWingPage::updateImageAndDescription() { @@ -129,5 +128,4 @@ void FixedWingPage::updateImageAndDescription() ui->typeGraphicsView->fitInView(m_fixedwingPic, Qt::KeepAspectRatio); ui->typeDescription->setText(description); - } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h index 5c50adcba..e74d91f67 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h @@ -62,7 +62,6 @@ private: private slots: void updateImageAndDescription(); - }; #endif // FIXEDWINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 385e4705b..41f92770e 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -30,7 +30,7 @@ #include "systemalarms.h" #include "uavobjectmanager.h" -const QString OutputCalibrationPage::MULTI_SVG_FILE = QString(":/setupwizard/resources/multirotor-shapes.svg"); +const QString OutputCalibrationPage::MULTI_SVG_FILE = QString(":/setupwizard/resources/multirotor-shapes.svg"); const QString OutputCalibrationPage::FIXEDWING_SVG_FILE = QString(":/setupwizard/resources/fixedwing-shapes-wizard.svg"); OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *parent) : @@ -42,8 +42,8 @@ OutputCalibrationPage::OutputCalibrationPage(SetupWizard *wizard, QWidget *paren qDebug() << "calling output calibration page"; m_vehicleRenderer = new QSvgRenderer(); - // move the code that was here to setupVehicle() so we can determine which image to use. - m_vehicleScene = new QGraphicsScene(this); + // move the code that was here to setupVehicle() so we can determine which image to use. + m_vehicleScene = new QGraphicsScene(this); ui->vehicleView->setScene(m_vehicleScene); } @@ -283,7 +283,7 @@ void OutputCalibrationPage::setWizardPage() ui->motorNeutralSlider->setValue(m_actuatorSettings[currentChannel].channelNeutral); } else if (currentPageIndex == 2) { if (m_actuatorSettings[currentChannel].channelMax < m_actuatorSettings[currentChannel].channelMin && - !ui->reverseCheckbox->isChecked()) { + !ui->reverseCheckbox->isChecked()) { ui->reverseCheckbox->setChecked(true); } else { ui->reverseCheckbox->setChecked(false); @@ -369,7 +369,7 @@ void OutputCalibrationPage::on_motorNeutralButton_toggled(bool checked) { ui->motorNeutralButton->setText(checked ? tr("Stop") : tr("Start")); ui->motorNeutralSlider->setEnabled(checked); - quint16 channel = getCurrentChannel(); + quint16 channel = getCurrentChannel(); quint16 safeValue = m_actuatorSettings[channel].channelNeutral; onStartButtonToggle(ui->motorNeutralButton, channel, m_actuatorSettings[channel].channelNeutral, safeValue, ui->motorNeutralSlider); } @@ -457,7 +457,7 @@ void OutputCalibrationPage::on_servoButton_toggled(bool checked) { ui->servoButton->setText(checked ? tr("Stop") : tr("Start")); quint16 channel = getCurrentChannel(); - quint16 safeValue = m_actuatorSettings[channel].channelNeutral; + quint16 safeValue = m_actuatorSettings[channel].channelNeutral; onStartButtonToggle(ui->servoButton, channel, safeValue, safeValue, ui->servoCenterAngleSlider); } @@ -497,17 +497,17 @@ void OutputCalibrationPage::on_servoMinAngleSlider_valueChanged(int position) // Adjust neutral and max if (ui->reverseCheckbox->isChecked()) { - if(value <= m_actuatorSettings[getCurrentChannel()].channelNeutral) { + if (value <= m_actuatorSettings[getCurrentChannel()].channelNeutral) { ui->servoCenterAngleSlider->setValue(value); } - if(value <= m_actuatorSettings[getCurrentChannel()].channelMax) { + if (value <= m_actuatorSettings[getCurrentChannel()].channelMax) { ui->servoMaxAngleSlider->setValue(value); } } else { - if(value >= m_actuatorSettings[getCurrentChannel()].channelNeutral) { + if (value >= m_actuatorSettings[getCurrentChannel()].channelNeutral) { ui->servoCenterAngleSlider->setValue(value); } - if(value >= m_actuatorSettings[getCurrentChannel()].channelMax) { + if (value >= m_actuatorSettings[getCurrentChannel()].channelMax) { ui->servoMaxAngleSlider->setValue(value); } } @@ -523,17 +523,17 @@ void OutputCalibrationPage::on_servoMaxAngleSlider_valueChanged(int position) // Adjust neutral and min if (ui->reverseCheckbox->isChecked()) { - if(value >= m_actuatorSettings[getCurrentChannel()].channelNeutral) { + if (value >= m_actuatorSettings[getCurrentChannel()].channelNeutral) { ui->servoCenterAngleSlider->setValue(value); } - if(value >= m_actuatorSettings[getCurrentChannel()].channelMin) { + if (value >= m_actuatorSettings[getCurrentChannel()].channelMin) { ui->servoMinAngleSlider->setValue(value); } } else { - if(value <= m_actuatorSettings[getCurrentChannel()].channelNeutral) { + if (value <= m_actuatorSettings[getCurrentChannel()].channelNeutral) { ui->servoCenterAngleSlider->setValue(value); } - if(value <= m_actuatorSettings[getCurrentChannel()].channelMin) { + if (value <= m_actuatorSettings[getCurrentChannel()].channelMin) { ui->servoMinAngleSlider->setValue(value); } } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp index a9c476cdc..6f1e25359 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.cpp @@ -59,6 +59,6 @@ bool VehiclePage::validatePage() void VehiclePage::initializePage() { - //ui->fixedwingButton->setEnabled(getWizard()->getControllerType() == SetupWizard::CONTROLLER_REVO || - // getWizard()->getControllerType() == SetupWizard::CONTROLLER_NANO); + // ui->fixedwingButton->setEnabled(getWizard()->getControllerType() == SetupWizard::CONTROLLER_REVO || + // getWizard()->getControllerType() == SetupWizard::CONTROLLER_NANO); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index d18e59345..4598f02f9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -148,7 +148,8 @@ int SetupWizard::nextId() const switch (getVehicleType()) { case VEHICLE_FIXEDWING: return PAGE_AIRFRAMESTAB_FIXEDWING; - //TODO: Pages for Multi and heli + + // TODO: Pages for Multi and heli case VEHICLE_MULTI: case VEHICLE_HELI: case VEHICLE_SURFACE: @@ -255,7 +256,7 @@ QString SetupWizard::getSummaryText() break; case VEHICLE_FIXEDWING: - summary.append(tr("Fixed wing")); + summary.append(tr("Fixed wing")); summary.append("
"); summary.append("").append(tr("Vehicle sub type: ")).append(""); @@ -272,7 +273,7 @@ QString SetupWizard::getSummaryText() default: summary.append(tr("Unknown")); break; - } + } break; case VEHICLE_HELI: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 148604c47..c5c8b8536 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -40,10 +40,10 @@ #include "revocalibration.h" #include "accelgyrosettings.h" -const qint16 VehicleConfigurationHelper::LEGACY_ESC_FREQUENCE = 50; -const qint16 VehicleConfigurationHelper::RAPID_ESC_FREQUENCE = 400; -const qint16 VehicleConfigurationHelper::ANALOG_SERVO_FREQUENCE = 50; -const qint16 VehicleConfigurationHelper::DIGITAL_SERVO_FREQUENCE = 333; +const qint16 VehicleConfigurationHelper::LEGACY_ESC_FREQUENCE = 50; +const qint16 VehicleConfigurationHelper::RAPID_ESC_FREQUENCE = 400; +const qint16 VehicleConfigurationHelper::ANALOG_SERVO_FREQUENCE = 50; +const qint16 VehicleConfigurationHelper::DIGITAL_SERVO_FREQUENCE = 333; VehicleConfigurationHelper::VehicleConfigurationHelper(VehicleConfigurationSource *configSource) : m_configSource(configSource), m_uavoManager(0), @@ -254,6 +254,7 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() ActuatorSettings *actSettings = ActuatorSettings::GetInstance(m_uavoManager); qint16 escFrequence = LEGACY_ESC_FREQUENCE; + switch (m_configSource->getEscType()) { case VehicleConfigurationSource::ESC_STANDARD: escFrequence = LEGACY_ESC_FREQUENCE; @@ -302,7 +303,7 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() // Servo always on channel 4 data.ChannelUpdateFreq[0] = escFrequence; if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_CC || - m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_CC3D) { + m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_CC3D) { data.ChannelUpdateFreq[1] = servoFrequence; } else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) { data.ChannelUpdateFreq[1] = escFrequence; @@ -1549,7 +1550,6 @@ void VehicleConfigurationHelper::setupOctoCopter() void VehicleConfigurationHelper::setupElevon() { - mixerChannelSettings channels[10]; GUIConfigDataUnion guiSettings = getGUIConfigData(); @@ -1559,7 +1559,7 @@ void VehicleConfigurationHelper::setupElevon() channels[2].throttle2 = 0; channels[2].roll = 0; channels[2].pitch = 0; - channels[2].yaw = 0; + channels[2].yaw = 0; // Elevon Servo 1 (Chan 1) channels[0].type = MIXER_TYPE_SERVO; @@ -1567,7 +1567,7 @@ void VehicleConfigurationHelper::setupElevon() channels[0].throttle2 = 0; channels[0].roll = -100; channels[0].pitch = 100; - channels[0].yaw = 0; + channels[0].yaw = 0; // Elevon Servo 1 (Chan 2) channels[1].type = MIXER_TYPE_SERVO; @@ -1575,11 +1575,11 @@ void VehicleConfigurationHelper::setupElevon() channels[1].throttle2 = 0; channels[1].roll = 100; channels[1].pitch = -100; - channels[1].yaw = 0; + channels[1].yaw = 0; guiSettings.fixedwing.FixedWingThrottle = 3; - guiSettings.fixedwing.FixedWingPitch1 = 1; - guiSettings.fixedwing.FixedWingPitch2 = 2; + guiSettings.fixedwing.FixedWingPitch1 = 1; + guiSettings.fixedwing.FixedWingPitch2 = 2; applyMixerConfiguration(channels); applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON, guiSettings); @@ -1601,7 +1601,7 @@ void VehicleConfigurationHelper::setupDualAileron() channels[2].throttle2 = 0; channels[2].roll = 0; channels[2].pitch = 0; - channels[2].yaw = 0; + channels[2].yaw = 0; // Aileron Servo 1 (Chan 1) channels[0].type = MIXER_TYPE_SERVO; @@ -1609,7 +1609,7 @@ void VehicleConfigurationHelper::setupDualAileron() channels[0].throttle2 = 0; channels[0].roll = -100; channels[0].pitch = 0; - channels[0].yaw = 0; + channels[0].yaw = 0; // Aileron Servo 2 (Chan 6) channels[5].type = MIXER_TYPE_SERVO; @@ -1617,7 +1617,7 @@ void VehicleConfigurationHelper::setupDualAileron() channels[5].throttle2 = 0; channels[5].roll = 100; channels[5].pitch = 0; - channels[5].yaw = 0; + channels[5].yaw = 0; // Elevator Servo (Chan 2) channels[1].type = MIXER_TYPE_SERVO; @@ -1625,7 +1625,7 @@ void VehicleConfigurationHelper::setupDualAileron() channels[1].throttle2 = 0; channels[1].roll = 0; channels[1].pitch = 100; - channels[1].yaw = 0; + channels[1].yaw = 0; // Rudder Servo (Chan 4) channels[3].type = MIXER_TYPE_SERVO; @@ -1633,13 +1633,13 @@ void VehicleConfigurationHelper::setupDualAileron() channels[3].throttle2 = 0; channels[3].roll = 0; channels[3].pitch = 0; - channels[3].yaw = 100; + channels[3].yaw = 100; guiSettings.fixedwing.FixedWingThrottle = 3; - guiSettings.fixedwing.FixedWingRoll1 = 1; - guiSettings.fixedwing.FixedWingRoll2 = 6; - guiSettings.fixedwing.FixedWingPitch1 = 2; - guiSettings.fixedwing.FixedWingYaw1 = 4; + guiSettings.fixedwing.FixedWingRoll1 = 1; + guiSettings.fixedwing.FixedWingRoll2 = 6; + guiSettings.fixedwing.FixedWingPitch1 = 2; + guiSettings.fixedwing.FixedWingYaw1 = 4; applyMixerConfiguration(channels); applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWING, guiSettings); @@ -1661,7 +1661,7 @@ void VehicleConfigurationHelper::setupAileron() channels[2].throttle2 = 0; channels[2].roll = 0; channels[2].pitch = 0; - channels[2].yaw = 0; + channels[2].yaw = 0; // Aileron Servo (Chan 1) channels[0].type = MIXER_TYPE_SERVO; @@ -1669,7 +1669,7 @@ void VehicleConfigurationHelper::setupAileron() channels[0].throttle2 = 0; channels[0].roll = 100; channels[0].pitch = 0; - channels[0].yaw = 0; + channels[0].yaw = 0; // Elevator Servo (Chan 2) channels[1].type = MIXER_TYPE_SERVO; @@ -1677,7 +1677,7 @@ void VehicleConfigurationHelper::setupAileron() channels[1].throttle2 = 0; channels[1].roll = 0; channels[1].pitch = 100; - channels[1].yaw = 0; + channels[1].yaw = 0; // Rudder Servo (Chan 4) channels[3].type = MIXER_TYPE_SERVO; @@ -1685,12 +1685,12 @@ void VehicleConfigurationHelper::setupAileron() channels[3].throttle2 = 0; channels[3].roll = 0; channels[3].pitch = 0; - channels[3].yaw = 100; + channels[3].yaw = 100; guiSettings.fixedwing.FixedWingThrottle = 3; - guiSettings.fixedwing.FixedWingRoll1 = 1; - guiSettings.fixedwing.FixedWingPitch1 = 2; - guiSettings.fixedwing.FixedWingYaw1 = 4; + guiSettings.fixedwing.FixedWingRoll1 = 1; + guiSettings.fixedwing.FixedWingPitch1 = 2; + guiSettings.fixedwing.FixedWingYaw1 = 4; applyMixerConfiguration(channels); applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWING, guiSettings); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 2102bf4d9..f666a1d35 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -72,8 +72,8 @@ public: virtual VehicleConfigurationSource::VEHICLE_TYPE getVehicleType() const = 0; virtual VehicleConfigurationSource::VEHICLE_SUB_TYPE getVehicleSubType() const = 0; virtual VehicleConfigurationSource::INPUT_TYPE getInputType() const = 0; - virtual VehicleConfigurationSource::ESC_TYPE getEscType() const = 0; - virtual VehicleConfigurationSource::SERVO_TYPE getServoType() const = 0; + virtual VehicleConfigurationSource::ESC_TYPE getEscType() const = 0; + virtual VehicleConfigurationSource::SERVO_TYPE getServoType() const = 0; virtual VehicleConfigurationSource::GPS_SETTING getGPSSetting() const = 0; virtual VehicleConfigurationSource::RADIO_SETTING getRadioSetting() const = 0; From a215bca34cb7c8f0a1571522849b194d7402eb7d Mon Sep 17 00:00:00 2001 From: m_thread Date: Wed, 27 Aug 2014 00:30:05 +0200 Subject: [PATCH 086/203] OP-1222 Added fixed wings to connection diagram dialog. --- .../plugins/setupwizard/connectiondiagram.ui | 3 + .../resources/connection-diagrams.svg | 5011 +++++++++++++++-- 2 files changed, 4425 insertions(+), 589 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.ui b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.ui index 7e86a99a2..8a4c5bf1f 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.ui @@ -40,6 +40,9 @@ + + QPainter::HighQualityAntialiasing|QPainter::TextAntialiasing +
diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg index f62e09121..2db84822c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -25,23 +25,124 @@ guidetolerance="10" inkscape:pageopacity="0" inkscape:pageshadow="2" - inkscape:window-width="1280" - inkscape:window-height="928" + inkscape:window-width="1920" + inkscape:window-height="1176" id="namedview4616" showgrid="false" - inkscape:zoom="0.64157228" - inkscape:cx="660.0971" - inkscape:cy="259.75717" - inkscape:window-x="0" - inkscape:window-y="27" + inkscape:zoom="1.8146404" + inkscape:cx="679.15232" + inkscape:cy="270.4075" + inkscape:window-x="1600" + inkscape:window-y="24" inkscape:window-maximized="1" - inkscape:current-layer="layer2" + inkscape:current-layer="svg12651" fit-margin-top="15" fit-margin-left="15" fit-margin-right="15" - fit-margin-bottom="15" /> + fit-margin-bottom="15" + inkscape:snap-grids="true" + showguides="true" + inkscape:guide-bbox="true"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -2187,7 +2636,8 @@ + transform="translate(-1.2734359,-1.2734359)" + style="display:inline"> @@ -2243,7 +2693,7 @@ @@ -2265,7 +2715,7 @@ @@ -2290,7 +2740,7 @@ @@ -2303,7 +2753,7 @@ @@ -2340,7 +2790,7 @@ @@ -2365,7 +2815,7 @@ @@ -2376,32 +2826,32 @@ @@ -2415,7 +2865,7 @@ @@ -2437,7 +2887,7 @@ @@ -2462,7 +2912,7 @@ @@ -2473,22 +2923,22 @@ @@ -2739,30 +3189,30 @@ @@ -2795,7 +3245,7 @@ @@ -2823,7 +3273,7 @@ @@ -2844,7 +3294,7 @@ @@ -2862,7 +3312,7 @@ @@ -2885,7 +3335,7 @@ @@ -2911,7 +3361,7 @@ @@ -2937,7 +3387,7 @@ @@ -2963,7 +3413,7 @@ @@ -2989,7 +3439,7 @@ @@ -3015,7 +3465,7 @@ @@ -3041,7 +3491,7 @@ @@ -3052,89 +3502,89 @@ @@ -3151,19 +3601,19 @@ style="fill:none;stroke:#777777;stroke-width:7.5;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:7.5, 15;stroke-dashoffset:0" inkscape:connector-curvature="0" stroke-miterlimit="4" - d="m 1820,829 l 197,-1.99 l 0,0" + d="m 1820,829 197,-1.99 0,0" id="path9655" /> @@ -3211,7 +3661,7 @@ @@ -3228,7 +3678,7 @@ @@ -3245,7 +3695,7 @@ @@ -3262,7 +3712,7 @@ @@ -3284,7 +3734,7 @@ @@ -3310,7 +3760,7 @@ @@ -3335,7 +3785,7 @@ @@ -3361,7 +3811,7 @@ @@ -3386,7 +3836,7 @@ @@ -3411,7 +3861,7 @@ @@ -3436,7 +3886,7 @@ @@ -3461,7 +3911,7 @@ @@ -3472,69 +3922,69 @@ @@ -3550,32 +4000,32 @@ style="fill:none;stroke:#777777;stroke-width:7.5;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:7.5, 15;stroke-dashoffset:0" inkscape:connector-curvature="0" stroke-miterlimit="4" - d="m 1820,706 l 106.7606,0.38448 l 0.5077,-67.0056 L 2240.39,638.42" + d="m 1820,706 106.7606,0.38448 0.5077,-67.0056 L 2240.39,638.42" id="path9822" sodipodi:nodetypes="cccc" /> @@ -3652,7 +4102,7 @@ @@ -3669,7 +4119,7 @@ @@ -3686,7 +4136,7 @@ @@ -3709,7 +4159,7 @@ @@ -3735,7 +4185,7 @@ @@ -3761,7 +4211,7 @@ @@ -3787,7 +4237,7 @@ @@ -3813,7 +4263,7 @@ @@ -3839,7 +4289,7 @@ @@ -3865,7 +4315,7 @@ @@ -3891,7 +4341,7 @@ @@ -3902,12 +4352,12 @@ @@ -3921,7 +4371,7 @@ @@ -3944,7 +4394,7 @@ @@ -3970,7 +4420,7 @@ @@ -3981,32 +4431,32 @@ @@ -4020,7 +4470,7 @@ @@ -4042,7 +4492,7 @@ @@ -4068,7 +4518,7 @@ @@ -4079,42 +4529,42 @@ @@ -4133,13 +4583,13 @@ @@ -4184,7 +4634,7 @@ @@ -4206,7 +4656,7 @@ @@ -4231,7 +4681,7 @@ @@ -4251,7 +4701,7 @@ @@ -4273,7 +4723,7 @@ @@ -4298,7 +4748,7 @@ @@ -4318,7 +4768,7 @@ @@ -4340,7 +4790,7 @@ @@ -4365,7 +4815,7 @@ @@ -4376,32 +4826,32 @@ @@ -4439,7 +4889,7 @@ @@ -4465,7 +4915,7 @@ @@ -4486,7 +4936,7 @@ @@ -4509,7 +4959,7 @@ @@ -4534,7 +4984,7 @@ @@ -4554,7 +5004,7 @@ @@ -4577,7 +5027,7 @@ @@ -4603,7 +5053,7 @@ @@ -4614,77 +5064,77 @@ @@ -4714,7 +5164,7 @@ style="fill:none;stroke:#777777;stroke-width:7.5;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:7.5, 22.5;stroke-dashoffset:0" inkscape:connector-curvature="0" stroke-miterlimit="4" - d="m 1820,864 l 487,2.81 l 1.41,115 m -488,-76 l 556,-1.41 l -1.41,104" + d="m 1820,864 487,2.81 1.41,115 m -488,-76 556,-1.41 -1.41,104" id="path9858" /> @@ -4753,7 +5203,7 @@ @@ -4778,7 +5228,7 @@ @@ -4789,40 +5239,40 @@ @@ -4836,7 +5286,7 @@ @@ -4858,7 +5308,7 @@ @@ -4883,7 +5333,7 @@ @@ -4894,7 +5344,7 @@ @@ -4908,7 +5358,7 @@ @@ -4930,7 +5380,7 @@ @@ -4955,7 +5405,7 @@ @@ -4968,7 +5418,7 @@ @@ -5005,7 +5455,7 @@ @@ -5030,7 +5480,7 @@ @@ -5041,22 +5491,22 @@ @@ -5134,7 +5584,7 @@ @@ -5160,7 +5610,7 @@ @@ -5171,7 +5621,7 @@ @@ -5209,7 +5659,7 @@ @@ -5235,7 +5685,7 @@ @@ -5252,44 +5702,44 @@ @@ -5297,41 +5747,41 @@ inkscape:groupmode="layer" id="layer10" inkscape:label="hexa-x" - style="display:inline"> + style="display:none"> @@ -5377,7 +5827,7 @@ transform="matrix(0.8660254,0.5,-0.5,0.8660254,968.3076,-983.2254)"> @@ -5393,7 +5843,7 @@ transform="translate(2515.9893,1514.8203)"> @@ -5411,7 +5861,7 @@ transform="translate(2355.4863,1607.2334)"> @@ -5429,7 +5879,7 @@ transform="translate(2516.0371,1330.8896)"> @@ -5447,7 +5897,7 @@ transform="translate(2354.9951,1235.6455)"> @@ -5470,7 +5920,7 @@ id="g19856"> @@ -5496,7 +5946,7 @@ id="g19870"> @@ -5522,7 +5972,7 @@ id="g19884"> @@ -5548,7 +5998,7 @@ id="g19898"> @@ -5574,7 +6024,7 @@ id="g19912"> @@ -5600,7 +6050,7 @@ id="g19926"> @@ -5626,7 +6076,7 @@ id="g19940"> @@ -5652,7 +6102,7 @@ id="g19954"> @@ -5663,12 +6113,12 @@ @@ -5706,7 +6156,7 @@ id="g19980"> @@ -5732,7 +6182,7 @@ id="g19994"> @@ -5743,32 +6193,32 @@ @@ -5806,7 +6256,7 @@ id="g20028"> @@ -5832,7 +6282,7 @@ id="g20042"> @@ -5843,47 +6293,3430 @@ + + + @@ -6397,12 +10230,12 @@ id="rect10839" /> + d="M 203.083,1.012 H 19.572 c -7.224,0 -13.08,4.478 -13.08,10 V 201.05 c 0,5.522 5.855,10 13.08,10 h 183.512 c 7.223,0 13.079,-4.478 13.079,-10 V 11.012 c 0,-5.523 -5.857,-10 -13.08,-10 z M 19.523,204.315 c -3.92,0 -7.098,-3.178 -7.098,-7.097 0,-3.92 3.178,-7.097 7.098,-7.097 3.918,0 7.096,3.177 7.096,7.097 0,3.92 -3.178,7.097 -7.096,7.097 z M 19.522,21.924 c -3.919,0 -7.097,-3.178 -7.097,-7.097 0,-3.919 3.178,-7.097 7.097,-7.097 3.919,0 7.097,3.177 7.097,7.097 0,3.919 -3.178,7.097 -7.097,7.097 z m 182.942,182.064 c -3.92,0 -7.098,-3.178 -7.098,-7.098 0,-3.919 3.178,-7.096 7.098,-7.096 3.918,0 7.096,3.177 7.096,7.096 0,3.921 -3.178,7.098 -7.096,7.098 z m 0.194,-183.487 c -3.92,0 -7.098,-3.178 -7.098,-7.097 0,-3.919 3.178,-7.097 7.098,-7.097 3.918,0 7.096,3.177 7.096,7.097 -0.001,3.92 -3.178,7.097 -7.096,7.097 z" /> + d="m 110.126,10.926 0.563,1.734 c 3.82,-1.425 2.62,-7.761 -2.074,-6.405 4.021,-0.446 4.084,4.377 1.511,4.671 z" /> + d="m 108.854,7.167 -0.563,-1.734 c -3.82,1.425 -2.62,7.761 2.075,6.405 -4.021,0.446 -4.084,-4.377 -1.512,-4.671 z" /> + d="m 98.619,13.405 h -1.59 L 95.548,10.35 H 95.39 v 2.083 H 93.94 V 5.672 c 0.381,-0.009 1.283,-0.148 1.711,-0.148 0.437,0 0.949,0.019 1.396,0.25 0.734,0.372 1.134,1.154 1.087,2.558 -0.093,1.144 -0.502,1.692 -1.125,1.916 l 1.61,3.157 z m -1.936,-5.39 c 0,-0.576 -0.205,-1.199 -0.819,-1.199 -0.158,0 -0.333,0.018 -0.474,0.046 v 2.38 c 0.892,0.336 1.293,-0.389 1.293,-1.227 z" /> + d="m 103.88,10.359 0.707,-4.687 h 1.553 l -1.404,6.761 h -1.85 l -1.414,-6.761 h 1.562 l 0.708,4.687 0.074,0.567 0.064,-0.567 z" /> + d="M 116.558,10.573 V 5.672 h 1.487 v 4.817 c 0.009,0.456 0.038,0.818 0.651,0.818 0.613,0 0.642,-0.362 0.651,-0.818 V 5.672 h 1.487 v 4.901 c 0,1.376 -0.763,1.99 -2.139,1.99 -1.356,0 -2.137,-0.614 -2.137,-1.99 z" /> + d="m 121.022,6.946 0.102,-1.274 h 3.952 l 0.121,1.274 h -1.292 v 5.487 H 122.38 V 6.946 h -1.358 z" /> + d="m 127.177,9.029 c 0,-1.692 0.633,-3.542 2.604,-3.533 1.962,-0.009 2.595,1.841 2.586,3.533 0,1.711 -0.595,3.543 -2.586,3.534 -1.999,0.009 -2.584,-1.823 -2.604,-3.534 z m 1.563,0.019 c 0,0.93 0.186,2.269 1.041,2.306 0.847,-0.038 1.032,-1.376 1.032,-2.306 0,-0.921 -0.186,-2.111 -1.032,-2.167 -0.856,0.056 -1.041,1.246 -1.041,2.167 z" /> + d="m 35.028,179.497 c 0,1.104 -0.896,2 -2,2 H 6.084 c -1.104,0 -2,-0.896 -2,-2 l 2,-1.341 -2,-2.125 v -31 l 2,-2.375 -2,-1.288 c 0,-1.104 0.896,-2 2,-2 h 26.945 c 1.104,0 2,0.896 2,2 v 38.129 z" /> @@ -12149,7 +15982,7 @@ @@ -12183,32 +16016,32 @@ From dca5a92104646cb135a4331da9276fd1e9ed1cf8 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Wed, 27 Aug 2014 08:43:28 +1000 Subject: [PATCH 087/203] Replace with new version --- .../configfixedwingwidget.cpp | 488 ++++++++---------- 1 file changed, 221 insertions(+), 267 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 43291e243..31bee79b6 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file configfixedwidget.cpp - * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin @@ -36,40 +36,10 @@ #include #include #include -#include #include #include #include -const QString ConfigFixedWingWidget::CHANNELBOXNAME = QString("fixedWingChannelBox"); - -ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : - VehicleConfig(parent), m_aircraft(new Ui_FixedWingConfigWidget()), - plane(NULL) -{ - m_aircraft->setupUi(this); - - plane = new QGraphicsSvgItem(); - populateChannelComboBoxes(); - - QStringList fixedWingTypes; - fixedWingTypes << "Aileron" << "Elevon"; - m_aircraft->fixedWingType->addItems(fixedWingTypes); - - // Set default model to "Aileron" - m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Aileron")); - - setupUI(m_aircraft->fixedWingType->currentText()); - - connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); - updateEnableControls(); -} - -ConfigFixedWingWidget::~ConfigFixedWingWidget() -{ - delete m_aircraft; -} - QStringList ConfigFixedWingWidget::getChannelDescriptions() { // init a channel_numelem list of channel desc defaults @@ -81,65 +51,72 @@ QStringList ConfigFixedWingWidget::getChannelDescriptions() // get the gui config data GUIConfigDataUnion configData = getConfigData(); - fixedGUISettingsStruct fixed = configData.fixedwing; - if (fixed.FixedWingThrottle > 0 && fixed.FixedWingThrottle <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingThrottle - 1] = QString("WingThrottle"); + if (configData.fixedwing.FixedWingPitch1 > 0) { + channelDesc[configData.fixedwing.FixedWingPitch1 - 1] = QString("FixedWingPitch1"); } - if (fixed.FixedWingPitch1 > 0 && fixed.FixedWingPitch1 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingPitch1 - 1] = QString("FixedWingPitch1"); + if (configData.fixedwing.FixedWingPitch2 > 0) { + channelDesc[configData.fixedwing.FixedWingPitch2 - 1] = QString("FixedWingPitch2"); } - if (fixed.FixedWingPitch2 > 0 && fixed.FixedWingPitch2 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingPitch2 - 1] = QString("FixedWingPitch2"); + if (configData.fixedwing.FixedWingRoll1 > 0) { + channelDesc[configData.fixedwing.FixedWingRoll1 - 1] = QString("FixedWingRoll1"); } - if (fixed.FixedWingRoll1 > 0 && fixed.FixedWingRoll1 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingRoll1 - 1] = QString("FixedWingRoll1"); + if (configData.fixedwing.FixedWingRoll2 > 0) { + channelDesc[configData.fixedwing.FixedWingRoll2 - 1] = QString("FixedWingRoll2"); } - if (fixed.FixedWingRoll2 > 0 && fixed.FixedWingRoll2 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingRoll2 - 1] = QString("FixedWingRoll2"); + if (configData.fixedwing.FixedWingYaw1 > 0) { + channelDesc[configData.fixedwing.FixedWingYaw1 - 1] = QString("FixedWingYaw1"); } - if (fixed.FixedWingYaw1 > 0 && fixed.FixedWingYaw1 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingYaw1 - 1] = QString("FixedWingYaw1"); + if (configData.fixedwing.FixedWingYaw2 > 0) { + channelDesc[configData.fixedwing.FixedWingYaw2 - 1] = QString("FixedWingYaw2"); } - if (fixed.FixedWingYaw2 > 0 && fixed.FixedWingYaw2 <= ConfigFixedWingWidget::CHANNEL_NUMELEM) { - channelDesc[fixed.FixedWingYaw2 - 1] = QString("FixedWingYaw2"); + if (configData.fixedwing.FixedWingThrottle > 0) { + channelDesc[configData.fixedwing.FixedWingThrottle - 1] = QString("FixedWingThrottle"); } return channelDesc; } -void ConfigFixedWingWidget::resetChannelboxesAndSliders() +ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : + VehicleConfig(parent), m_aircraft(new Ui_FixedWingConfigWidget()) { - m_aircraft->fwRudder1ChannelBox->setEnabled(false); - m_aircraft->fwRudder2ChannelBox->setEnabled(false); - m_aircraft->fwElevator1ChannelBox->setEnabled(false); - m_aircraft->fwElevator2ChannelBox->setEnabled(false); - m_aircraft->fwAileron1ChannelBox->setEnabled(false); - m_aircraft->fwAileron2ChannelBox->setEnabled(false); - m_aircraft->elevonSlider1->setEnabled(false); - m_aircraft->elevonSlider2->setEnabled(false); + m_aircraft->setupUi(this); + + planeimg = new QGraphicsSvgItem(); + + populateChannelComboBoxes(); + + QStringList fixedWingTypes; + fixedWingTypes << "Aileron" << "Elevon" << "Vtail"; + m_aircraft->fixedWingType->addItems(fixedWingTypes); + + // Set default model to "Aileron" + connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); + m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Aileron")); + setupUI(m_aircraft->fixedWingType->currentText()); } +ConfigFixedWingWidget::~ConfigFixedWingWidget() +{ + delete m_aircraft; +} + +/** + Virtual function to setup the UI + */ void ConfigFixedWingWidget::setupUI(QString frameType) { Q_ASSERT(m_aircraft); - Q_ASSERT(plane); - // This had to be moved from ConfigFixedWingWidget() here since m_aircraft->fixedWingType->currentText() - // did not seem to work properly to choose alternate .svg files. m_aircraft->planeShape->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); m_aircraft->planeShape->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); QSvgRenderer *renderer = new QSvgRenderer(); renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); - plane = new QGraphicsSvgItem(); - plane->setSharedRenderer(renderer); - - qDebug() << "Current Aircraft type: \n" << m_aircraft->fixedWingType->currentText(); + planeimg = new QGraphicsSvgItem(); + planeimg->setSharedRenderer(renderer); if (frameType == "FixedWing" || frameType == "Aileron") { - plane->setElementId("aileron"); + planeimg->setElementId("aileron"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Aileron")); - resetChannelboxesAndSliders(); - m_aircraft->fwRudder1ChannelBox->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true); m_aircraft->fwElevator1ChannelBox->setEnabled(true); @@ -151,58 +128,54 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwAileron2Label->setText("Aileron 2"); m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); - } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { - // do nothing for now + + m_aircraft->elevonSlider1->setEnabled(false); + m_aircraft->elevonSlider2->setEnabled(false); } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { - plane->setElementId("elevon"); + planeimg->setElementId("elevon"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); - resetChannelboxesAndSliders(); - - m_aircraft->fwElevator1Label->setText("Elevon 1"); - m_aircraft->fwElevator1ChannelBox->setEnabled(true); - - m_aircraft->fwElevator2Label->setText("Elevon 2"); - m_aircraft->fwElevator2ChannelBox->setEnabled(true); - - m_aircraft->fwAileron1Label->setText("Aileron 1"); - m_aircraft->fwAileron2Label->setText("Aileron 2"); + m_aircraft->fwAileron1Label->setText("Elevon 1"); + m_aircraft->fwAileron2Label->setText("Elevon 2"); + m_aircraft->fwElevator1ChannelBox->setEnabled(false); + m_aircraft->fwElevator1ChannelBox->setCurrentIndex(0); + m_aircraft->fwElevator2ChannelBox->setEnabled(false); + m_aircraft->fwElevator2ChannelBox->setCurrentIndex(0); + m_aircraft->fwRudder1ChannelBox->setEnabled(true); + m_aircraft->fwRudder2ChannelBox->setEnabled(true); + m_aircraft->fwElevator1Label->setText("Elevator 1"); + m_aircraft->fwElevator2Label->setText("Elevator 2"); m_aircraft->elevonLabel1->setText("Roll"); m_aircraft->elevonLabel2->setText("Pitch"); m_aircraft->elevonSlider1->setEnabled(true); m_aircraft->elevonSlider2->setEnabled(true); - } + } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { + planeimg->setElementId("vtail"); + setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail")); + m_aircraft->fwRudder1ChannelBox->setEnabled(false); + m_aircraft->fwRudder1ChannelBox->setCurrentIndex(0); + m_aircraft->fwRudder2ChannelBox->setEnabled(false); + m_aircraft->fwRudder2ChannelBox->setCurrentIndex(0); + m_aircraft->fwElevator1Label->setText("Vtail 1"); + m_aircraft->fwElevator1ChannelBox->setEnabled(true); + m_aircraft->fwElevator2Label->setText("Vtail 2"); + m_aircraft->fwElevator2ChannelBox->setEnabled(true); + + m_aircraft->fwAileron1Label->setText("Aileron 1"); + m_aircraft->fwAileron2Label->setText("Aileron 2"); + m_aircraft->elevonLabel1->setText("Rudder"); + m_aircraft->elevonLabel2->setText("Pitch"); + + m_aircraft->elevonSlider1->setEnabled(true); + m_aircraft->elevonSlider2->setEnabled(true); + } QGraphicsScene *scene = new QGraphicsScene(); - scene->addItem(plane); - scene->setSceneRect(plane->boundingRect()); + scene->addItem(planeimg); + scene->setSceneRect(planeimg->boundingRect()); m_aircraft->planeShape->setScene(scene); - setupEnabledControls(frameType); - // Draw the appropriate airframe - updateAirframe(frameType); -} - -void ConfigFixedWingWidget::setupEnabledControls(QString frameType) -{ - // disable all motor channel boxes - for (int i = 1; i <= 8; i++) { - // do it manually so we can turn off any error decorations - QComboBox *combobox = this->findChild("fixedWingChannelBox" + QString::number(i)); - if (combobox) { - combobox->setEnabled(false); - combobox->setItemData(0, 0, Qt::DecorationRole); - } - } - - if (frameType == "Vtail" || frameType == "vtail") { - // enableComboBoxes(this, CHANNELBOXNAME, 3, true); - } else if (frameType == "Elevon" || frameType == "Elevon") { - enableComboBoxes(this, CHANNELBOXNAME, 3, true); - } else if (frameType == "aileron" || frameType == "Aileron") { - enableComboBoxes(this, CHANNELBOXNAME, 4, true); - } } void ConfigFixedWingWidget::registerWidgets(ConfigTaskWidget &parent) @@ -266,11 +239,13 @@ void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType) setComboCurrentIndex(m_aircraft->fwAileron2ChannelBox, fixed.FixedWingRoll2); setComboCurrentIndex(m_aircraft->fwElevator1ChannelBox, fixed.FixedWingPitch1); setComboCurrentIndex(m_aircraft->fwElevator2ChannelBox, fixed.FixedWingPitch2); + setComboCurrentIndex(m_aircraft->fwRudder1ChannelBox, fixed.FixedWingYaw1); + setComboCurrentIndex(m_aircraft->fwRudder2ChannelBox, fixed.FixedWingYaw2); if (frameType == "FixedWingElevon") { // If the airframe is elevon, restore the slider setting // Find the channel number for Elevon1 (FixedWingRoll1) - int channel = m_aircraft->fwElevator1ChannelBox->currentIndex() - 1; + int channel = m_aircraft->fwAileron1ChannelBox->currentIndex() - 1; if (channel > -1) { // If for some reason the actuators were incoherent, we might fail here, hence the check. m_aircraft->elevonSlider1->setValue( @@ -278,111 +253,49 @@ void ConfigFixedWingWidget::refreshWidgetsValues(QString frameType) m_aircraft->elevonSlider2->setValue( getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH) * 100); } + } else if (frameType == "FixedWingVtail") { + int channel = m_aircraft->fwElevator1ChannelBox->currentIndex() - 1; + if (channel > -1) { + // If for some reason the actuators were incoherent, we might fail here, hence the check. + m_aircraft->elevonSlider1->setValue( + getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW) * 100); + m_aircraft->elevonSlider2->setValue( + getMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH) * 100); + } } - - updateAirframe(frameType); } /** - Helper function to update the UI widget objects + Virtual function to update the UI widget objects */ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() { + QString airframeType = "FixedWing"; + + // Save the curve (common to all Fixed wing frames) UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); Q_ASSERT(mixer); - // Curve is also common to all quads: - setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->fixedWingThrottle->getCurve()); - - QString airframeType; - QList motor_servo_List; - - if (m_aircraft->fixedWingType->currentText() == "Aileron") { - airframeType = "FixedWing"; - setupFrameFixedWing(airframeType); - - motor_servo_List << "FixedWingThrottle" << "FixedWingPitch1" << "FixedWingPitch2" << "FixedWingRoll1" << "FixedWingRoll2" << "FixedWingYaw1" << "FixedWingYaw2"; - setupMotors(motor_servo_List); - - GUIConfigDataUnion config = getConfigData(); - setConfigData(config); - - m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); - } else if (m_aircraft->fixedWingType->currentText() == "elevon") { - airframeType = "FixedWingElevon"; - setupFrameElevon(airframeType); - - motor_servo_List << "FixedWingThrottle" << "FixedWingRoll1" << "FixedWingRoll2"; - setupMotors(motor_servo_List); - - GUIConfigDataUnion config = getConfigData(); - setConfigData(config); - - // Elevon Layout: - // pitch roll yaw - double mixerMatrix[8][3] = { - { 0, 0, 0 }, - { 1, -1, 0 }, - { -1, 1, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 }, - { 0, 0, 0 } - }; - setupFixedWingElevonMixer(mixerMatrix); - - m_aircraft->fwStatusLabel->setText(tr("Configuration OK")); - } - // Remove Feed Forward, it is pointless on a plane: setMixerValue(mixer, "FeedForward", 0.0); - return airframeType; -} + // Set the throttle curve + setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->fixedWingThrottle->getCurve()); -void ConfigFixedWingWidget::setupMotors(QList motorList) -{ - QList mmList; - mmList << m_aircraft->fwEngineChannelBox << m_aircraft->fwAileron1ChannelBox - << m_aircraft->fwAileron2ChannelBox << m_aircraft->fwElevator1ChannelBox - << m_aircraft->fwElevator2ChannelBox << m_aircraft->fwRudder1ChannelBox - << m_aircraft->fwRudder2ChannelBox; - - GUIConfigDataUnion configData = getConfigData(); - resetActuators(&configData); - - foreach(QString motor, motorList) { - int index = mmList.takeFirst()->currentIndex(); - - if (motor == QString("FixedWingThrottle")) { - configData.fixedwing.FixedWingThrottle = index; - } else if (motor == QString("FixedWingPitch1")) { - configData.fixedwing.FixedWingPitch1 = index; - } else if (motor == QString("FixedWingPitch2")) { - configData.fixedwing.FixedWingPitch2 = index; - } else if (motor == QString("FixedWingRoll1")) { - configData.fixedwing.FixedWingRoll1 = index; - } else if (motor == QString("FixedWingRoll2")) { - configData.fixedwing.FixedWingRoll2 = index; - } else if (motor == QString("FixedWingYaw1")) { - configData.fixedwing.FixedWingYaw1 = index; - } else if (motor == QString("FixedWingYaw2")) { - configData.fixedwing.FixedWingYaw1 = index; - } + // All airframe types must start with "FixedWing" + if (m_aircraft->fixedWingType->currentText() == "Aileron") { + airframeType = "FixedWing"; + setupFrameFixedWing(airframeType); + } else if (m_aircraft->fixedWingType->currentText() == "Elevon") { + airframeType = "FixedWingElevon"; + setupFrameElevon(airframeType); + } else { // "Vtail" + airframeType = "FixedWingVtail"; + setupFrameVtail(airframeType); } - setConfigData(configData); -} -void ConfigFixedWingWidget::updateAirframe(QString frameType) -{ - qDebug() << "ConfigFixedWingWidget::updateAirframe - frame type" << frameType; - - // this is not doing anything right now - - m_aircraft->planeShape->setSceneRect(plane->boundingRect()); - m_aircraft->planeShape->fitInView(plane, Qt::KeepAspectRatio); + return airframeType; } /** @@ -409,7 +322,6 @@ bool ConfigFixedWingWidget::setupFrameFixedWing(QString airframeType) config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex(); config.fixedwing.FixedWingYaw1 = m_aircraft->fwRudder1ChannelBox->currentIndex(); - config.fixedwing.FixedWingYaw2 = m_aircraft->fwRudder2ChannelBox->currentIndex(); config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex(); setConfigData(config); @@ -475,6 +387,76 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) GUIConfigDataUnion config = getConfigData(); resetActuators(&config); + config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); + config.fixedwing.FixedWingRoll2 = m_aircraft->fwAileron2ChannelBox->currentIndex(); + config.fixedwing.FixedWingYaw1 = m_aircraft->fwRudder1ChannelBox->currentIndex(); + config.fixedwing.FixedWingYaw2 = m_aircraft->fwRudder2ChannelBox->currentIndex(); + config.fixedwing.FixedWingThrottle = m_aircraft->fwEngineChannelBox->currentIndex(); + + setConfigData(config); + + UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + Q_ASSERT(mixer); + resetMotorAndServoMixers(mixer); + + // Save the curve: + // ... and compute the matrix: + // In order to make code a bit nicer, we assume: + // - Channel dropdowns start with 'None', then 0 to 7 + + // 1. Assign the servo/motor/none for each channel + + double value; + + // motor + int channel = m_aircraft->fwEngineChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); + + // rudders + channel = m_aircraft->fwRudder1ChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + + channel = m_aircraft->fwRudder2ChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127); + + // ailerons + channel = m_aircraft->fwAileron1ChannelBox->currentIndex() - 1; + if (channel > -1) { + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + value = (double)(m_aircraft->elevonSlider2->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + value = (double)(m_aircraft->elevonSlider1->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, value); + + channel = m_aircraft->fwAileron2ChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + value = (double)(m_aircraft->elevonSlider2->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + value = (double)(m_aircraft->elevonSlider1->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -value); + } + + m_aircraft->fwStatusLabel->setText("Mixer generated"); + return true; +} + +/** + Setup VTail + */ +bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType) +{ + // Check coherence: + // Show any config errors in GUI + if (throwConfigError(airframeType)) { + return false; + } + + GUIConfigDataUnion config = getConfigData(); + resetActuators(&config); + config.fixedwing.FixedWingPitch1 = m_aircraft->fwElevator1ChannelBox->currentIndex(); config.fixedwing.FixedWingPitch2 = m_aircraft->fwElevator2ChannelBox->currentIndex(); config.fixedwing.FixedWingRoll1 = m_aircraft->fwAileron1ChannelBox->currentIndex(); @@ -499,6 +481,15 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_MOTOR); setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_THROTTLECURVE1, 127); + // rudders + channel = m_aircraft->fwRudder1ChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, 127); + + channel = m_aircraft->fwRudder2ChannelBox->currentIndex() - 1; + setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -127); + // ailerons channel = m_aircraft->fwAileron1ChannelBox->currentIndex() - 1; if (channel > -1) { @@ -510,64 +501,34 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -127); } - // elevon + // vtail channel = m_aircraft->fwElevator1ChannelBox->currentIndex() - 1; if (channel > -1) { setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, 127); + double value = (double)(m_aircraft->elevonSlider2->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + value = (double)(m_aircraft->elevonSlider1->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, value); channel = m_aircraft->fwElevator2ChannelBox->currentIndex() - 1; setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, -127); + value = (double)(m_aircraft->elevonSlider2->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + value = (double)(m_aircraft->elevonSlider1->value() * 1.27); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_YAW, -value); } m_aircraft->fwStatusLabel->setText("Mixer generated"); return true; } -/** - Helper function: setupElevonServo - */ -void ConfigFixedWingWidget::setupElevonServo(int channel, double pitch, double roll) +void ConfigFixedWingWidget::enableControls(bool enable) { - UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); + ConfigTaskWidget::enableControls(enable); - Q_ASSERT(mixer); - - setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, roll * 127); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, pitch * 127); -} - -/** - This function sets up the elevon fixed wing mixer values. - */ -bool ConfigFixedWingWidget::setupFixedWingElevonMixer(double mixerFactors[8][3]) -{ - UAVDataObject *mixer = dynamic_cast(getObjectManager()->getObject(QString("MixerSettings"))); - - Q_ASSERT(mixer); - resetMotorAndServoMixers(mixer); - - // and enable only the relevant channels: - double pFactor = (double)m_aircraft->elevonSlider1->value() / 100.0; - double rFactor = (double)m_aircraft->elevonSlider2->value() / 100.0; - - QList mmList; - mmList << m_aircraft->fwEngineChannelBox << m_aircraft->fwAileron1ChannelBox - << m_aircraft->fwAileron2ChannelBox << m_aircraft->fwElevator1ChannelBox - << m_aircraft->fwElevator2ChannelBox; - - for (int i = 0; i < 8; i++) { - if (mmList.at(i)->isEnabled()) { - int channel = mmList.at(i)->currentIndex() - 1; - if (channel > -1) { - setupElevonServo(channel, mixerFactors[i][0] * pFactor, rFactor * mixerFactors[i][1]); - } - } + if (enable) { + setupUI(m_aircraft->fixedWingType->currentText()); } - return true; } /** @@ -610,7 +571,27 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) m_aircraft->fwRudder1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } } else if (airframeType == "FixedWingElevon") { -/* + if (m_aircraft->fwEngineChannelBox->currentText() == "None") { + m_aircraft->fwEngineChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes + error = true; + } else { + m_aircraft->fwEngineChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + } + + if (m_aircraft->fwAileron1ChannelBox->currentText() == "None") { + m_aircraft->fwAileron1ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes + error = true; + } else { + m_aircraft->fwAileron1ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + } + + if (m_aircraft->fwAileron2ChannelBox->currentText() == "None") { + m_aircraft->fwAileron2ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes + error = true; + } else { + m_aircraft->fwAileron2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + } + } else if (airframeType == "FixedWingVtail") { if (m_aircraft->fwEngineChannelBox->currentText() == "None") { m_aircraft->fwEngineChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes error = true; @@ -629,9 +610,8 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) m_aircraft->fwElevator2ChannelBox->setItemData(0, pixmap, Qt::DecorationRole); // Set color palettes error = true; } else { - m_aircraft->fwElevator2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes + m_aircraft->fwElevator2ChannelBox->setItemData(0, 0, Qt::DecorationRole); // Reset color palettes } - */ } if (error) { @@ -640,29 +620,3 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) return error; } - -void ConfigFixedWingWidget::showEvent(QShowEvent *event) -{ - Q_UNUSED(event) - Q_ASSERT(plane); - m_aircraft->planeShape->fitInView(plane, Qt::KeepAspectRatio); -} - -/** - Resize the GUI contents when the user changes the window size - */ -void ConfigFixedWingWidget::resizeEvent(QResizeEvent *event) -{ - Q_UNUSED(event); - Q_ASSERT(plane); - m_aircraft->planeShape->fitInView(plane, Qt::KeepAspectRatio); -} - -void ConfigFixedWingWidget::enableControls(bool enable) -{ - ConfigTaskWidget::enableControls(enable); - - if (enable) { - setupEnabledControls(m_aircraft->fixedWingType->currentText()); - } -} From 73ef79a95e4df74415e0d5c1a1b8e16dc7df7d6d Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Wed, 27 Aug 2014 08:45:50 +1000 Subject: [PATCH 088/203] Header also --- .../cfg_vehicletypes/configfixedwingwidget.h | 20 +++++-------------- 1 file changed, 5 insertions(+), 15 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index 9fd56f8aa..f749d4ae0 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -44,7 +44,6 @@ class ConfigFixedWingWidget : public VehicleConfig { Q_OBJECT public: - static const QString CHANNELBOXNAME; static QStringList getChannelDescriptions(); ConfigFixedWingWidget(QWidget *parent = 0); @@ -53,29 +52,20 @@ public: virtual void refreshWidgetsValues(QString frameType); virtual QString updateConfigObjectsFromWidgets(); - void resetChannelboxesAndSliders(); -protected: - void showEvent(QShowEvent *event); - void resizeEvent(QResizeEvent *event); - void enableControls(bool enable); - private: Ui_FixedWingConfigWidget *m_aircraft; - QGraphicsSvgItem *plane; + QGraphicsSvgItem *planeimg; virtual void registerWidgets(ConfigTaskWidget &parent); virtual void resetActuators(GUIConfigDataUnion *configData); bool setupFrameFixedWing(QString airframeType); - bool setupFrameVtail(QString airframeType); bool setupFrameElevon(QString airframeType); - bool setupFixedWingMixer(double mixerFactors[8][3]); - bool setupFixedWingElevonMixer(double mixerFactors[8][3]); - void setupMotors(QList motorList); - void setupElevonServo(int channel, double roll, double pitch); + bool setupFrameVtail(QString airframeType); + +protected: + void enableControls(bool enable); - void updateAirframe(QString multiRotorType); - void setupEnabledControls(QString airframeType); private slots: virtual void setupUI(QString airframeType); virtual bool throwConfigError(QString airframeType); From 63c4392932aa6d6209f3c5a93ade54315032edaa Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Wed, 27 Aug 2014 18:13:45 +1000 Subject: [PATCH 089/203] Fix slider links, did this before but reator removed them due to wrong naming in the UI by me. --- .../src/plugins/config/airframe_fixedwing.ui | 50 ++++++++++++++++--- 1 file changed, 43 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui index 3732c7931..620f8a572 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui @@ -160,7 +160,7 @@ - Elevon Mix + Mixer @@ -218,7 +218,7 @@ margin:1px; - false + true @@ -241,7 +241,7 @@ margin:1px; - + 40 @@ -286,7 +286,7 @@ margin:1px; - false + true @@ -309,7 +309,7 @@ margin:1px; - + 40 @@ -699,6 +699,42 @@ margin:1px; 1 - - + + + + + + elevonSlider1 + valueChanged(int) + elevonSliderLabel1 + setNum(int) + + + 124 + 126 + + + 124 + 126 + + + + + elevonSlider2 + valueChanged(int) + elevonSliderLabel2 + setNum(int) + + + 362 + 299 + + + 124 + 126 + + + + + From 772ea8e0516402163dd8ce2d195a5e07a22b28f4 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 28 Aug 2014 05:58:14 +1000 Subject: [PATCH 090/203] Disable sliders by default, as default airframe is Aileron and on a clean board with no settings the mixer slider will be enabled. Use setCurrentText rather than relying on an index --- .../openpilotgcs/src/plugins/config/airframe_fixedwing.ui | 5 ++--- .../config/cfg_vehicletypes/configfixedwingwidget.cpp | 8 ++++---- 2 files changed, 6 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui index 620f8a572..a20b1f20b 100644 --- a/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui +++ b/ground/openpilotgcs/src/plugins/config/airframe_fixedwing.ui @@ -218,7 +218,7 @@ margin:1px; - true + false @@ -286,7 +286,7 @@ margin:1px; - true + false @@ -737,4 +737,3 @@ margin:1px; - diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 31bee79b6..3ba1df668 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -137,9 +137,9 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->fwAileron1Label->setText("Elevon 1"); m_aircraft->fwAileron2Label->setText("Elevon 2"); m_aircraft->fwElevator1ChannelBox->setEnabled(false); - m_aircraft->fwElevator1ChannelBox->setCurrentIndex(0); + m_aircraft->fwElevator1ChannelBox->setCurrentText("None"); m_aircraft->fwElevator2ChannelBox->setEnabled(false); - m_aircraft->fwElevator2ChannelBox->setCurrentIndex(0); + m_aircraft->fwElevator2ChannelBox->setCurrentText("None"); m_aircraft->fwRudder1ChannelBox->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true); @@ -154,9 +154,9 @@ void ConfigFixedWingWidget::setupUI(QString frameType) planeimg->setElementId("vtail"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail")); m_aircraft->fwRudder1ChannelBox->setEnabled(false); - m_aircraft->fwRudder1ChannelBox->setCurrentIndex(0); + m_aircraft->fwRudder1ChannelBox->setCurrentText("None"); m_aircraft->fwRudder2ChannelBox->setEnabled(false); - m_aircraft->fwRudder2ChannelBox->setCurrentIndex(0); + m_aircraft->fwRudder2ChannelBox->setCurrentText("None"); m_aircraft->fwElevator1Label->setText("Vtail 1"); m_aircraft->fwElevator1ChannelBox->setEnabled(true); From 271f6090b5fd64ae69d7e09272d7f18267a5f9d5 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 28 Aug 2014 06:43:34 +1000 Subject: [PATCH 091/203] Enable vtail again --- .../src/plugins/config/configvehicletypewidget.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index e113a921c..2ad4e1741 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -74,8 +74,7 @@ QStringList ConfigVehicleTypeWidget::getChannelDescriptions() channelDesc = ConfigFixedWingWidget::getChannelDescriptions(); break; case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL: - // do nothing for vtail support for the time being. - // channelDesc = ConfigFixedWingWidget::getChannelDescriptions(); + channelDesc = ConfigFixedWingWidget::getChannelDescriptions(); break; case SystemSettings::AIRFRAMETYPE_HELICP: // helicp From d87cf62c003ae8c7aa829f43889afe7e24c633cd Mon Sep 17 00:00:00 2001 From: m_thread Date: Wed, 27 Aug 2014 22:52:30 +0200 Subject: [PATCH 092/203] OP-1222 Added support for correct image scaling on open and resize. --- .../cfg_vehicletypes/configfixedwingwidget.cpp | 16 ++++++++++++++++ .../cfg_vehicletypes/configfixedwingwidget.h | 3 +++ 2 files changed, 19 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 3ba1df668..887bf5fdf 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -174,6 +174,7 @@ void ConfigFixedWingWidget::setupUI(QString frameType) QGraphicsScene *scene = new QGraphicsScene(); scene->addItem(planeimg); scene->setSceneRect(planeimg->boundingRect()); + m_aircraft->planeShape->fitInView(planeimg, Qt::KeepAspectRatio); m_aircraft->planeShape->setScene(scene); } @@ -620,3 +621,18 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) return error; } + + +void ConfigFixedWingWidget::resizeEvent(QResizeEvent *) +{ + if (planeimg) { + m_aircraft->planeShape->fitInView(planeimg, Qt::KeepAspectRatio); + } +} + +void ConfigFixedWingWidget::showEvent(QShowEvent *) +{ + if (planeimg) { + m_aircraft->planeShape->fitInView(planeimg, Qt::KeepAspectRatio); + } +} diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index f749d4ae0..e4bc8f115 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -65,10 +65,13 @@ private: protected: void enableControls(bool enable); + void resizeEvent(QResizeEvent *); + void showEvent(QShowEvent *); private slots: virtual void setupUI(QString airframeType); virtual bool throwConfigError(QString airframeType); + }; #endif // CONFIGFIXEDWINGWIDGET_H From 826048e92309f168c5087429ec4eb257d81c256e Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Fri, 29 Aug 2014 03:47:02 +0200 Subject: [PATCH 093/203] OP-1222 FW_Wizard SVG artwork connection-diagrams.svg Work in progress --- .../resources/connection-diagrams.svg | 27582 +++++++++------- 1 file changed, 16060 insertions(+), 11522 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg index 2db84822c..964a491af 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -2,6 +2,7 @@ + showguides="false" + inkscape:guide-bbox="true" + inkscape:snap-global="false"> + @@ -1404,135 +1409,6 @@ stop-color="#FFF" id="stop6616" /> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -2635,75 +5655,7992 @@ + + + + + + + + + + + + + + Throttle + Roll + Pitch + Yaw + Flight Mode + + + + + + + + + + + + + + + + + + + Spectrum + Satellite + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Nano + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#2f2d2e;fill-rule:nonzero" /> + style="fill:#c8c7c6;fill-rule:nonzero" /> + style="fill:#658acf;fill-rule:nonzero" /> + style="fill:#c8c7c6;fill-rule:nonzero" /> + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> - - + + - + + d="m 1820,829 l 174,-0.995 l 156,2.37 l 1.5918,172.7585" + stroke-miterlimit="4" + inkscape:connector-curvature="0" + style="fill:none;stroke:#777777;stroke-width:7.5;stroke-linecap:round;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:7.5, 15;stroke-dashoffset:0" /> + transform="translate(-4,0)" + id="g6079"> + id="g6081" + clip-path="url(#clipPath6065-8)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10102-8)" /> @@ -4298,12 +15238,12 @@ + transform="translate(-4,0)" + id="g6111"> + id="g6113" + clip-path="url(#clipPath6097-0)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10104-0)" /> @@ -4324,12 +15264,12 @@ + transform="translate(-4,0)" + id="g6143"> + id="g6145" + clip-path="url(#clipPath6129-2)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10106-6)" /> @@ -4350,39 +15290,39 @@ + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + id="g6175" + clip-path="url(#clipPath6169-2)" + style="opacity:0.5"> + id="g6177" + transform="translate(2191.2754,1327.0928)"> + style="fill:#b1c7eb;fill-rule:nonzero" /> + transform="translate(4,0)" + id="g6199"> + id="g6201" + clip-path="url(#clipPath6185-2)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10108-1)" /> @@ -4403,12 +15343,12 @@ + transform="translate(4,-4)" + id="g6231"> + id="g6233" + clip-path="url(#clipPath6217-8)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10110-9)" /> @@ -4429,58 +15369,58 @@ + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + id="g6279" + clip-path="url(#clipPath6273-5)" + style="opacity:0.5"> + id="g6281" + transform="translate(2193.8848,1514.2402)"> + style="fill:#b1c7eb;fill-rule:nonzero" /> + id="g6305" + clip-path="url(#clipPath6289-4)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10112-8)" /> @@ -4501,12 +15441,12 @@ + transform="translate(0,-4)" + id="g6335"> + id="g6337" + clip-path="url(#clipPath6321-0)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10114-4)" /> @@ -4527,124 +15467,125 @@ + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#2f2d2e;fill-rule:nonzero" /> + style="fill:#c8c7c6;fill-rule:nonzero" /> + style="fill:#658acf;fill-rule:nonzero" /> + style="fill:#c8c7c6;fill-rule:nonzero" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,897.30485,-993.42748)" + id="g19888"> + style="opacity:0.69999701" + clip-path="url(#clipPath6001-5)" + id="g19890"> + d="m 2220,1180 c 1.3,31.4 27.2,56.5 58.9,56.5 c 23.8,0.01 44.4,-14.1 53.7,-34.5 l -17.4,-17.4 c -3.24,9.35 -12.1,16.1 -22.6,16.1 c -12.1,0.01 -22.1,-8.99 -23.7,-20.6 h 11.1 l -10.3,-10.3 l -17.8,-17.8 l -7.46,-7.46 l -35.6,35.6 h 11.2 z" + id="path19900" /> @@ -6008,12 +16951,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,964.5025,-1057.7231)" + id="g19902"> + style="opacity:0.69999701" + clip-path="url(#clipPath6033-9)" + id="g19904"> + d="m 2480,1260 c -3.01,-9.77 -12.1,-16.9 -22.9,-16.9 c -12.2,0 -22.2,9.11 -23.7,20.9 h 12 l -35.6,35.6 l -35.6,-35.6 h 11.3 c 1.64,-31.1 27.4,-55.8 58.9,-55.8 c 23.6,-0.011 44,13.9 53.4,34 L 2480,1260 z" + id="path19914" /> @@ -6034,12 +16977,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,964.5025,-1057.7231)" + id="g19916"> + style="opacity:0.69999701" + clip-path="url(#clipPath6065-5)" + id="g19918"> + d="m 2530,1270 c -1.3,31.4 -27.2,56.5 -58.9,56.5 c -23.8,0.01 -44.4,-14.1 -53.7,-34.5 l 17.4,-17.4 c 3.24,9.35 12.1,16.1 22.6,16.1 c 12.1,0.01 22.1,-8.99 23.7,-20.6 H 2470 l 10.3,-10.3 l 17.8,-17.8 l 7.46,-7.46 l 35.6,35.6 h -11.2 z" + id="path19928" /> @@ -6060,12 +17003,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1079.7005,-945.89008)" + id="g19930"> + style="opacity:0.69999701" + clip-path="url(#clipPath6097-7)" + id="g19932"> + d="m 2320,1540 c -3.01,-9.77 -12.1,-16.9 -22.9,-16.9 c -12.2,0.01 -22.2,9.11 -23.7,20.9 h 12 l -35.6,35.6 l -35.6,-35.6 l 11.3,10e-4 c 1.64,-31.1 27.4,-55.8 58.9,-55.8 c 23.6,-0.011 44,13.9 53.4,34 l -17.8,17.8 z" + id="path19942" /> @@ -6086,12 +17029,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1079.7005,-945.89008)" + id="g19944"> + style="opacity:0.69999701" + clip-path="url(#clipPath6129-8)" + id="g19946"> + d="m 2370,1550 c -1.3,31.4 -27.2,56.5 -58.9,56.5 c -23.8,0.01 -44.4,-14.1 -53.7,-34.5 l 17.4,-17.4 c 3.24,9.35 12.1,16.1 22.6,16.1 c 12.1,0.01 22.1,-8.99 23.7,-20.6 H 2310 l 10.3,-10.3 l 17.8,-17.8 l 7.46,-7.46 l 35.6,35.6 l -11.2,10e-4 z" + id="path19956" /> @@ -6112,40 +17055,40 @@ + d="m 2301.6833,1565.5736 c 12.8456,-3.4493 20.4906,-16.6908 17.0413,-29.5364 c -3.4443,-12.8543 -16.6858,-20.4993 -29.5315,-17.05 c -12.8456,3.4493 -20.4906,16.6908 -17.0413,29.5364 c 3.4356,12.8493 16.6858,20.4993 29.5265,17.0587" + id="path19958" /> + d="m 2296.3628,1534.789 l -5.45,9.4397 l -1.3289,-3.2383 l -2.8349,1.2501 l 2.4399,5.554 l 2.7973,1.615 l 7.45,-12.9038 l -3.0571,-1.765 z" + id="path19960" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,919.09419,-895.85226)" + id="g19962"> + style="opacity:0.5" + clip-path="url(#clipPath6169-9)" + id="g19964"> + transform="translate(2191.2754,1327.0928)" + id="g19966"> + d="m 0,0 c 33.2,-33.2 33.2,-87.1 -0.047,-120 c -33.2,-33.2 -87.1,-33.2 -120,0 c -33.2,33.2 -33.2,87 0.008,120 c 32.9,33.2 86.8,33.2 120,0" + id="path19968" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,924.55829,-897.31636)" + id="g19970"> + style="opacity:0.69999701" + clip-path="url(#clipPath6185-0)" + id="g19972"> + d="m 2150,1260 c -3.01,-9.78 -12.1,-16.9 -22.9,-16.9 c -12.2,0.01 -22.2,9.11 -23.7,20.9 h 12 l -35.6,35.6 l -35.6,-35.6 h 11.3 c 1.64,-31.1 27.4,-55.8 58.9,-55.8 c 23.6,-0.01 44,13.9 53.4,34 L 2150,1260 z" + id="path19982" /> @@ -6166,12 +17109,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,924.55829,-897.31636)" + id="g19984"> + style="opacity:0.69999701" + clip-path="url(#clipPath6217-2)" + id="g19986"> + d="m 2200,1270 c -1.29,31.4 -27.2,56.5 -58.9,56.5 c -23.8,0.01 -44.4,-14.1 -53.7,-34.5 l 17.4,-17.4 c 3.24,9.35 12.1,16.1 22.6,16.1 c 12.1,0.01 22.1,-8.99 23.7,-20.6 H 2140 l 10.3,-10.3 l 17.8,-17.8 l 7.46,-7.46 l 35.6,35.6 h -11.2 z" + id="path19996" /> @@ -6192,60 +17135,60 @@ + d="m 2141.0488,1287.6603 c 12.8456,-3.4493 20.4906,-16.6909 17.0413,-29.5365 c -3.4443,-12.8543 -16.6858,-20.4993 -29.5314,-17.05 c -12.8457,3.4493 -20.4907,16.6908 -17.0414,29.5365 c 3.4443,12.8543 16.6859,20.4993 29.5265,17.0586" + id="path19998" /> + d="m 2139.1924,1258.8757 c -2.3469,-1.355 -5.0105,-1.2416 -6.783,0.4485 l 2.2859,2.4607 c 0.7887,-0.734 1.9689,-0.9302 2.9735,-0.3502 c 1.0392,0.6 1.555,1.7465 0.8425,2.9806 c -0.88,1.5242 -2.5206,1.1659 -3.7677,0.4459 c -0.9093,-0.525 -2.0983,-1.5256 -2.8187,-2.3779 l -3.9416,7.5392 l 7.8894,4.555 l 1.51,-2.6154 l -5.1788,-2.99 l 1.0668,-2.0977 c 0.3299,0.3106 0.8363,0.6514 1.2173,0.8714 c 2.5808,1.49 5.4593,1.3044 7.0193,-1.3976 c 1.805,-3.1263 0.2214,-6.0036 -2.3074,-7.4636" + id="path20000" /> + d="m 2460.5442,1474.9993 c 12.8457,-3.4493 20.4907,-16.6908 17.0414,-29.5365 c -3.4443,-12.8543 -16.6859,-20.4993 -29.5315,-17.05 c -12.8456,3.4493 -20.4906,16.6908 -17.0413,29.5365 c 3.4356,12.8493 16.6858,20.4993 29.5264,17.0586" + id="path20002" /> + d="m 2452.7596,1440.4826 l -1.47,2.5461 l 2.398,7.4467 c 0.29,0.9676 0.3615,1.8137 -0.088,2.5932 c -0.525,0.9093 -1.5265,1.174 -2.4921,0.6165 c -1.022,-0.59 -1.2268,-1.7752 -0.6937,-2.9986 l -3.1582,-1.2899 c -1.209,2.7661 0,5.5333 2.5154,6.9833 c 2.3643,1.365 5.3842,1.4343 6.9392,-1.2591 c 1.06,-1.8359 0.6061,-3.5298 0.038,-5.2664 l -1.4442,-4.3787 l 5.2568,3.035 l 1.53,-2.65 l -9.3531,-5.4 z" + id="path20004" /> + d="m 2300.8235,1195.6068 c 12.8457,-3.4492 20.4907,-16.6908 17.0414,-29.5364 c -3.4443,-12.8543 -16.6859,-20.4993 -29.5315,-17.05 c -12.8456,3.4493 -20.4993,16.6858 -17.0413,29.5364 c 3.4443,12.8543 16.6858,20.4993 29.5264,17.0587" + id="path20006" /> + d="m 2292.2351,1174.4825 l -0.055,-0.032 l -0.3071,-6.5281 l 3.1091,1.795 l -2.75,4.7631 z m 7.0205,-5.6 l 1.45,-2.5115 l -2.8578,-1.65 l -1.45,2.5115 l -6.0536,-3.495 l -1.48,2.5635 l 0.7345,10.8278 l 3.6546,2.11 l 4.555,-7.8894 l 1.784,1.03 l 1.43,-2.4769 l -1.7667,-1.02 z" + id="path20008" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1013.0175,-872.08396)" + id="g20010"> + style="opacity:0.5" + clip-path="url(#clipPath6273-8)" + id="g20012"> + transform="translate(2193.8848,1514.2402)" + id="g20014"> + d="m 0,0 c 33.2,-33.2 33.2,-87.1 -0.047,-120 c -33.2,-33.2 -87.1,-33.2 -120,0 c -33.2,33.2 -33.2,87 0.008,120 c 32.9,33.2 86.8,33.2 120,0" + id="path20016" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1013.0175,-872.08396)" + id="g20018"> + style="opacity:0.69999701" + clip-path="url(#clipPath6289-3)" + id="g20020"> + d="m 2110,1450 c 3.01,-9.77 12.1,-16.9 22.9,-16.9 c 12.2,0 22.2,9.11 23.7,20.9 h -12 l 35.6,35.6 l 35.6,-35.6 h -11.3 c -1.64,-31.1 -27.4,-55.8 -58.9,-55.8 c -23.6,-0.01 -44,13.9 -53.4,34 l 17.8,17.8 z" + id="path20030" /> @@ -6266,12 +17209,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1013.0175,-872.08396)" + id="g20032"> + style="opacity:0.69999701" + clip-path="url(#clipPath6321-6)" + id="g20034"> + d="m 2060,1460 c 1.3,31.4 27.2,56.5 58.9,56.5 c 23.8,0 44.4,-14.1 53.7,-34.5 l -17.4,-17.4 c -3.24,9.35 -12.1,16.1 -22.6,16.1 c -12.1,0.01 -22.1,-8.99 -23.7,-20.6 h 11.1 l -10.3,-10.3 l -17.8,-17.8 l -7.46,-7.46 l -35.6,35.6 h 11.2 z" + id="path20044" /> @@ -6292,709 +17235,718 @@ + d="m 2137.9721,1479.4375 c 12.8456,-3.4493 20.4993,-16.6858 17.0413,-29.5365 c -3.4443,-12.8543 -16.6858,-20.4993 -29.5314,-17.05 c -12.8457,3.4493 -20.4907,16.6908 -17.0414,29.5365 c 3.4443,12.8543 16.6859,20.4993 29.5265,17.0586" + id="path20046" /> + d="m 2132.1157,1457.5811 c -1.1951,-0.69 -1.5522,-2.0116 -0.8602,-3.2102 c 0.64,-1.1085 1.9752,-1.5731 3.1929,-0.8701 c 1.2037,0.695 1.5348,2.0015 0.8328,3.2174 c -0.67,1.1605 -1.9652,1.5559 -3.1655,0.8629 m 3.8018,-6.627 c -2.7973,-1.615 -6.1049,-1.1459 -7.7299,1.6686 c -0.88,1.5242 -0.983,3.0467 -0.8624,4.8138 l 0.434,6.4282 l 3.6893,2.13 l -0.621,-6.2244 l 0,-0.1225 c 0.184,0.2275 0.5353,0.503 0.8254,0.6705 c 2.2516,1.3 5.1925,0.7463 6.6425,-1.7652 c 1.69,-2.9272 0.4051,-6.0015 -2.3749,-7.6065" + id="path20048" /> + d="m 2466.0494,1289.5215 c 12.8543,-3.4443 20.4993,-16.6858 17.0413,-29.5365 c -3.4443,-12.8543 -16.6858,-20.4993 -29.5315,-17.05 c -12.8456,3.4493 -20.4993,16.6859 -17.0413,29.5365 c 3.4443,12.8543 16.6858,20.4993 29.5265,17.0587" + id="path20050" /> + d="m 2463.7425,1258.6545 c -2.3469,-1.355 -5.0586,-1.558 -7.1365,0.4408 l 2.4096,2.3866 c 0.7304,-0.7192 1.9469,-1.0122 3.1074,-0.3422 c 0.8747,0.505 1.6186,1.5165 0.9256,2.7168 c -0.755,1.3077 -2.326,0.9087 -3.5904,0.1787 l -0.8193,-0.473 l -1.29,2.2344 l 0.892,0.515 c 1.1432,0.66 2.0837,1.591 1.3717,2.8242 c -0.535,0.9266 -1.602,0.9688 -2.4395,0.4853 c -0.8746,-0.505 -1.242,-1.4688 -0.9366,-2.4576 l -3.2186,-0.9853 c -0.6317,2.5221 0.7687,4.8086 2.9078,6.0436 c 2.269,1.31 5.1993,1.4545 6.6293,-1.0223 c 0.82,-1.4203 0.5207,-3.0019 -0.5501,-4.0473 l 0.031,-0.054 c 1.6544,0.4945 3.3668,-0.1115 4.1968,-1.5491 c 1.63,-2.8233 -0.1341,-5.5277 -2.4984,-6.8927" + id="path20052" /> + d="m 2253.9161,1368.6254 l 53.7802,31.05 c 1.4116,0.815 3.2148,0.3318 4.0298,-1.0798 l 31.05,-53.7802 c 0.815,-1.4116 0.3368,-3.2234 -1.0748,-4.0384 l -53.7802,-31.05 c -1.4116,-0.815 -3.2147,-0.3319 -4.0347,1.0884 l -31.05,53.7802 c -0.815,1.4116 -0.3319,3.2148 1.0797,4.0298" + id="path20054" /> + d="m 2293.4328,1352.1805 l 2.2925,-9.5306 l 8.1707,0.1678 l -2.9972,10.9713 l -7.476,-1.5912 z m -10.0002,13.7408 l 3.526,-12.1671 l 2.0699,0.3348 l 11.5979,2.1119 l -2.3556,10.06 l -14.7934,-0.3772 z m 4.4851,17.8316 c -1.0069,-0.556 -1.6539,-1.4953 -1.3253,-2.9245 l 3.3013,-13.7979 l 7.3955,0.1706 l -2.8751,10.5798 c 0.068,1.4709 1.2914,1.6232 2.7296,1.5922 l 11.4788,-0.682 c 1.0848,-0.1808 2.0425,-0.7376 2.7542,-2.0703 l 3.6823,-7.5619 c 0.4921,-1.0784 0.2296,-2.0498 -0.2965,-2.2266 l -17.2786,-0.4726 l 2.7704,-10.1784 l 3.8743,0.6895 l 0.01,-0.01 l 15.9086,2.8456 c 2.3697,0.4155 2.8766,3.5776 1.0759,6.8565 l -6.6437,11.6372 c -1.6975,2.8421 -3.9703,3.5968 -6.0009,3.9139 l -15.9486,2.2237 c -1.3505,0.2191 -3.2912,0.1205 -4.6089,-0.6172" + id="path20056" /> + d="m 2281.2367,1361.3049 l -1.5125,-3e-4 l -1.1255,4.2692 l -3.3237,-0.083 l -4.2072,-5.5929 l -8.874,-2.4098 l 9.5166,-0.6833 l 6.3797,-4.8499 l 4.1241,0.8569 l -1.2788,4.7349 l 1.1718,0.4503 l -0.8704,3.3195 z" + id="path20058" /> + d="m 2324.2174,1346.86 l 2.217,1.28 c 0.2425,0.14 0.4866,0.1573 0.7504,0.09 c 0.1315,-0.026 0.2519,-0.084 0.3432,-0.1644 c 0.1032,-0.077 0.1966,-0.1706 0.2671,-0.2927 l 0.457,-0.7915 c 0.068,-0.117 0.1036,-0.2474 0.1239,-0.3846 c 0.02,-0.1122 0.01,-0.238 -0.037,-0.3656 c -0.072,-0.2655 -0.2099,-0.4664 -0.4524,-0.6064 l -2.217,-1.28 c -0.2381,-0.1375 -0.489,-0.1611 -0.7488,-0.087 c -0.1345,0.025 -0.247,0.078 -0.3438,0.1456 c -0.099,0.092 -0.1984,0.1856 -0.2659,0.3026 l -0.457,0.7915 c -0.07,0.1221 -0.1008,0.2525 -0.1251,0.3747 c -0.014,0.1245 -0.01,0.2562 0.038,0.3844 c 0.068,0.2585 0.2127,0.4657 0.4508,0.6032 m -10.7387,-6.2 l 2.217,1.28 c 0.2399,0.1385 0.4848,0.1563 0.7452,0.087 c 0.2589,-0.067 0.4798,-0.2149 0.6173,-0.4531 l 0.457,-0.7915 c 0.1385,-0.2399 0.1616,-0.5141 0.08,-0.7542 c -0.063,-0.2583 -0.2056,-0.4639 -0.4359,-0.5969 l -3.0917,-1.785 l -0.496,0.8591 l -0.2605,0.4512 l -0.1965,0.3403 c -0.071,0.1221 -0.1042,0.2505 -0.1208,0.3772 c -0.013,0.125 0,0.2602 0.041,0.3859 c 0.057,0.2525 0.2005,0.4587 0.4438,0.5992 m -12.9903,-7.5 l 2.2083,1.275 c 0.2486,0.1435 0.4926,0.1608 0.7565,0.094 c 0.1262,-0.029 0.2424,-0.09 0.3406,-0.1659 c 0.1049,-0.076 0.194,-0.1721 0.2605,-0.2873 l -3.9318,-2.27 c -0.066,0.1152 -0.1019,0.2426 -0.1193,0.3688 c -0.014,0.1245 -0.01,0.2557 0.032,0.3809 c 0.069,0.259 0.2204,0.4702 0.4542,0.6052 m -6.5038,-3.755 l 2.1997,1.27 c 0.2433,0.1405 0.5029,0.1668 0.7677,0.1003 c 0.2641,-0.063 0.4563,-0.2284 0.5938,-0.4666 l 0.457,-0.7915 c 0.1385,-0.2399 0.1903,-0.4976 0.1032,-0.7407 c -0.073,-0.266 -0.2264,-0.4759 -0.4697,-0.6164 l -1.6368,-0.945 l -1.4203,-0.82 l -0.496,0.8591 l -0.2605,0.4512 l -0.1965,0.3403 c -0.07,0.1221 -0.1172,0.243 -0.1303,0.3717 c 0,0.1305 0,0.2632 0.038,0.3844 c 0.061,0.2545 0.2143,0.4667 0.4577,0.6072 m -6.5125,-3.76 l 2.1997,1.27 c 0.2399,0.1385 0.5056,0.1683 0.7634,0.098 c 0.1202,-0.032 0.2354,-0.094 0.3423,-0.1649 c 0.1032,-0.077 0.1871,-0.1761 0.2576,-0.2982 l 0.457,-0.7915 c 0.068,-0.117 0.1131,-0.2419 0.1334,-0.3791 c 0,-0.1212 0,-0.244 -0.036,-0.3651 c -0.066,-0.262 -0.2255,-0.4754 -0.4654,-0.6139 l -0.2754,-0.159 l -1.9226,-1.11 c -0.2442,-0.141 -0.4985,-0.1666 -0.767,-0.098 c -0.1155,0.036 -0.2323,0.086 -0.3308,0.1531 c -0.113,0.084 -0.1941,0.1881 -0.2616,0.3051 l -0.457,0.7915 c -0.07,0.1221 -0.1189,0.242 -0.1294,0.3722 c -0.012,0.1255 0,0.2597 0.025,0.3769 c 0.076,0.2635 0.2248,0.4727 0.469,0.6137 m 36.1995,22.1007 c -0.2416,-0.1395 -0.4458,-0.314 -0.6064,-0.5418 c -0.1569,-0.1922 -0.2704,-0.4356 -0.326,-0.6732 c -0.073,-0.2602 -0.091,-0.5211 -0.069,-0.7927 c 0.034,-0.2735 0.1379,-0.5208 0.2744,-0.7572 l 0.465,-0.8054 c 0.1405,-0.2434 0.3029,-0.4568 0.5196,-0.618 c 0.2223,-0.1511 0.4552,-0.2626 0.7159,-0.328 c 0.2336,-0.071 0.5011,-0.094 0.749,-0.059 c 0.2766,0.027 0.5278,0.1199 0.7694,0.2594 l 2.3296,1.345 c 0.2399,0.1385 0.4478,0.3105 0.605,0.5341 c 0.1574,0.1994 0.2727,0.4437 0.3387,0.6874 c 0.069,0.2559 0.088,0.5129 0.064,0.778 c -0.04,0.2632 -0.1288,0.5191 -0.2693,0.7625 l -0.465,0.8054 c -0.1365,0.2364 -0.3137,0.4412 -0.5247,0.6127 c -0.2191,0.1576 -0.4532,0.273 -0.7105,0.3427 c -0.244,0.065 -0.5133,0.087 -0.7617,0.045 c -0.2732,-0.023 -0.5281,-0.1132 -0.768,-0.2517 l -2.3296,-1.345 z m -23.7291,-13.7 c -0.2382,-0.1375 -0.4432,-0.3125 -0.6081,-0.5428 c -0.1604,-0.1942 -0.2696,-0.4351 -0.3304,-0.6757 c -0.067,-0.2567 -0.091,-0.5216 -0.062,-0.7887 c 0.033,-0.2722 0.1189,-0.5179 0.2574,-0.7578 l 0.465,-0.8054 c 0.1385,-0.2399 0.3121,-0.4445 0.5326,-0.6105 c 0.2156,-0.1573 0.4584,-0.27 0.713,-0.3389 c 0.2388,-0.068 0.502,-0.093 0.7534,-0.057 c 0.2809,0.029 0.5329,0.1229 0.7711,0.2604 l 3.5594,2.055 l -0.52,0.9007 l -3.5074,-2.025 c -0.2339,-0.135 -0.4916,-0.1626 -0.7523,-0.089 c -0.1031,0.031 -0.1952,0.072 -0.2844,0.1326 c -0.097,0.055 -0.1803,0.1303 -0.2441,0.2089 l 4.8757,2.815 l -0.53,0.918 c -0.1385,0.2398 -0.3116,0.4355 -0.5181,0.6073 c -0.2243,0.1545 -0.4515,0.274 -0.7157,0.3396 c -0.2466,0.063 -0.5124,0.088 -0.7677,0.042 c -0.2603,-0.015 -0.5152,-0.1058 -0.7681,-0.2518 l -2.3209,-1.34 z m -12.9904,-7.5 c -0.2511,-0.145 -0.4561,-0.32 -0.6029,-0.5398 c -0.1733,-0.2017 -0.2773,-0.4396 -0.3494,-0.6867 c -0.064,-0.2552 -0.087,-0.5191 -0.059,-0.7872 c 0.04,-0.27 0.1275,-0.5268 0.264,-0.7632 l 0.465,-0.8054 c 0.1405,-0.2434 0.3194,-0.4473 0.53,-0.612 c 0.2163,-0.1546 0.4544,-0.2631 0.7064,-0.3335 c 0.2501,-0.061 0.5081,-0.09 0.7724,-0.046 c 0.2628,0.019 0.5148,0.1124 0.7659,0.2574 l 1.7407,1.005 l 0.5751,0.332 l 2.4248,1.4 l 0.995,-1.7234 l 0.9613,0.555 l -0.995,1.7234 l 0.8037,0.464 l 0.3118,0.18 l 2.0091,1.16 c 0.2451,0.1415 0.4487,0.311 0.5981,0.5301 c 0.1721,0.2079 0.277,0.4462 0.3543,0.6964 c 0.073,0.2579 0.088,0.5129 0.056,0.7735 c -0.038,0.2642 -0.1202,0.5241 -0.2607,0.7675 l -0.465,0.8054 c -0.1365,0.2364 -0.3206,0.4372 -0.5333,0.6077 c -0.2113,0.1621 -0.4419,0.2795 -0.7027,0.3472 c -0.2553,0.058 -0.5142,0.086 -0.7773,0.036 c -0.2654,-0.018 -0.516,-0.1062 -0.7611,-0.2477 l -2.3209,-1.34 c -0.2434,-0.1405 -0.4475,-0.315 -0.6038,-0.5403 c -0.1664,-0.1977 -0.273,-0.4371 -0.3451,-0.6842 c -0.067,-0.2572 -0.091,-0.5211 -0.055,-0.7847 c 0.033,-0.274 0.1171,-0.5328 0.2536,-0.7692 l 0.955,-1.6541 l -0.8834,-0.51 c -0.01,0.067 -0.01,0.1434 -0.02,0.2066 c -0.027,0.2708 -0.1141,0.5277 -0.2546,0.771 l -0.465,0.8054 c -0.1365,0.2365 -0.3154,0.4403 -0.5394,0.6043 c -0.2018,0.1675 -0.4428,0.279 -0.6923,0.3531 c -0.2553,0.058 -0.5185,0.084 -0.7755,0.037 c -0.2768,-0.025 -0.5299,-0.1143 -0.7733,-0.2548 l -2.3209,-1.34 z m 33.2339,13.4372 l 0.9526,0.55 l -2.5,4.3301 l -0.9526,-0.55 l 2.5,-4.3301 z m -13.7583,-2.1699 c -0.2364,-0.1365 -0.4373,-0.3206 -0.594,-0.5531 c -0.1535,-0.1902 -0.2653,-0.4326 -0.3313,-0.6763 c -0.067,-0.2566 -0.088,-0.5196 -0.065,-0.7901 c 0.043,-0.2663 0.1336,-0.5095 0.2721,-0.7493 l 1.48,-2.5635 l 0.944,0.545 l -1.475,2.5548 c -0.1365,0.2364 -0.1595,0.5003 -0.094,0.7623 c 0.024,0.1179 0.093,0.2358 0.1559,0.3359 c 0.079,0.1056 0.1735,0.1856 0.2921,0.2541 l 2.2257,1.285 c 0.1143,0.066 0.2388,0.1125 0.3566,0.1204 c 0.1322,0.013 0.2728,0.015 0.3784,-0.027 c 0.2676,-0.07 0.4785,-0.2249 0.615,-0.4613 l 1.475,-2.5548 l 0.265,0.153 l 0.6799,0.3925 l 0.6737,0.389 l 0.995,-1.7234 l 0.9527,0.55 l -0.995,1.7234 l 0.8028,0.4635 l 1.9918,1.15 l 0.3525,0.2035 c 0.2295,0.1325 0.4374,0.3045 0.5972,0.5296 c 0.1522,0.1964 0.2675,0.4408 0.3335,0.6844 c 0.066,0.254 0.093,0.5154 0.064,0.7785 c -0.035,0.2663 -0.1358,0.5151 -0.2763,0.7585 l -0.465,0.8054 c -0.1365,0.2364 -0.3015,0.4483 -0.5177,0.6167 c -0.2157,0.1596 -0.4576,0.2705 -0.7114,0.3422 c -0.244,0.065 -0.5133,0.087 -0.7565,0.048 c -0.2758,-0.024 -0.5307,-0.1147 -0.7602,-0.2472 l -2.3469,-1.355 c -0.2417,-0.1395 -0.4458,-0.3139 -0.6029,-0.5398 c -0.1509,-0.1887 -0.2583,-0.4285 -0.3313,-0.6762 c -0.069,-0.2582 -0.091,-0.5211 -0.068,-0.7922 c 0.041,-0.2694 0.1301,-0.5253 0.2666,-0.7617 l 0.955,-1.6541 l -0.6738,-0.389 l -0.955,1.6541 l 0,0.01 c -0.1385,0.2398 -0.3124,0.435 -0.5129,0.6103 c -0.2252,0.154 -0.4584,0.27 -0.7157,0.3396 c -0.2483,0.062 -0.5176,0.085 -0.7668,0.042 c -0.2607,-0.01 -0.5215,-0.091 -0.7648,-0.2314 l -2.3383,-1.35 z m 21.4552,14.0384 l 0.61,-1.0566 l -0.4243,-0.245 l 0.525,-0.9093 l 0.4243,0.245 l 1.065,-1.8446 c 0.1405,-0.2434 0.3264,-0.4432 0.5309,-0.6115 c 0.2189,-0.1531 0.4466,-0.2675 0.7012,-0.3365 c 0.257,-0.057 0.5124,-0.087 0.7776,-0.043 c 0.2611,0.018 0.5139,0.1119 0.7659,0.2574 l 0.6851,0.3955 l -0.52,0.9007 l -0.6729,-0.3885 c -0.2464,-0.1134 -0.501,-0.1403 -0.7351,-0.055 c -0.1221,0.02 -0.241,0.081 -0.3371,0.1599 c -0.095,0.066 -0.1723,0.1684 -0.2388,0.2836 l -1.06,1.836 l 1.4896,0.86 l -0.1115,0.1931 l -0.415,0.7188 l -1.4896,-0.86 l -0.61,1.0565 l -0.9613,-0.555 z m -9.6345,-4.9124 l 2.48,-4.2955 c 0.1385,-0.2399 0.3224,-0.4385 0.5378,-0.6075 c 0.2086,-0.1613 0.4384,-0.2815 0.6944,-0.3369 c 0.2622,-0.06 0.5107,-0.089 0.7901,-0.049 c 0.261,0.018 0.5052,0.107 0.7529,0.25 l 0.1914,0.1105 l -0.52,0.9007 l -0.1741,-0.1005 c -0.2394,-0.1094 -0.4784,-0.1273 -0.735,-0.055 c -0.1152,0.024 -0.2315,0.087 -0.325,0.1668 c -0.1079,0.059 -0.1749,0.167 -0.2414,0.2821 l -2.48,4.2955 l -0.9699,-0.56 z m -1.0608,-1.8827 l 0.9526,0.55 l -0.55,0.9527 l -0.9526,-0.55 l 0.55,-0.9527 z" + id="path20060" /> + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - Spectrum - Satellite - - - - - - - - - - - - Futaba - S-Bus - - - - - - - - - - - - PPM Signal - - - - - - - - - - - - - - - - - Throttle - Roll - Pitch - Yaw - Flight Mode - - + transform="translate(1.2734359,1.2734359)" /> From c39424d50ac188dd8f1d8255b8407d390a8c55f0 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Fri, 29 Aug 2014 16:04:28 +0200 Subject: [PATCH 094/203] OP-1222_FW_Wizard : Finished artwork diagram, cpp file. Wing tips for FW, polished Vtail and all frames in dark gray. --- .../config/images/fixedwing-shapes.svg | 248 +- .../plugins/setupwizard/connectiondiagram.cpp | 27 +- .../resources/connection-diagrams.svg | 4522 +++++---- .../fixedwing-shapes-wizard-no-numbers.svg | 45 +- .../resources/fixedwing-shapes-wizard.svg | 8192 +++++++++-------- 5 files changed, 6930 insertions(+), 6104 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index b9c6266b3..9b5a425b0 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -483,19 +483,20 @@ guidetolerance="10" inkscape:pageopacity="0" inkscape:pageshadow="2" - inkscape:window-width="1920" - inkscape:window-height="1017" + inkscape:window-width="1280" + inkscape:window-height="928" id="namedview4099" showgrid="false" - inkscape:zoom="0.3535534" - inkscape:cx="413.32337" - inkscape:cy="1244.5763" - inkscape:window-x="-8" - inkscape:window-y="-8" + inkscape:zoom="0.73144533" + inkscape:cx="784.15573" + inkscape:cy="958.96697" + inkscape:window-x="0" + inkscape:window-y="27" inkscape:window-maximized="1" - inkscape:current-layer="Layer_1" + inkscape:current-layer="elevon" showborder="true" - inkscape:showpageshadow="false" />getInputType()) { case VehicleConfigurationSource::INPUT_PWM: - elementsToShow << "pwm"; + if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { + elementsToShow << "pwm-nano"; + } else { + elementsToShow << "pwm"; + } break; case VehicleConfigurationSource::INPUT_PPM: - elementsToShow << "ppm"; + if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { + elementsToShow << "ppm-nano"; + } else { + elementsToShow << "ppm"; + } break; case VehicleConfigurationSource::INPUT_SBUS: - elementsToShow << "sbus"; + if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { + elementsToShow << "sbus-nano"; + } else { + elementsToShow << "sbus"; + } break; case VehicleConfigurationSource::INPUT_DSMX10: case VehicleConfigurationSource::INPUT_DSMX11: case VehicleConfigurationSource::INPUT_DSM2: - elementsToShow << "satellite"; + if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { + elementsToShow << "satellite-nano"; + } else { + elementsToShow << "satellite"; + } break; default: break; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg index 964a491af..02ee18011 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -30,13 +30,13 @@ inkscape:window-height="928" id="namedview4616" showgrid="false" - inkscape:zoom="0.96009689" - inkscape:cx="657.23521" - inkscape:cy="315.42386" + inkscape:zoom="0.70710678" + inkscape:cx="642.99304" + inkscape:cy="214.47045" inkscape:window-x="0" inkscape:window-y="27" inkscape:window-maximized="1" - inkscape:current-layer="layer35" + inkscape:current-layer="layer18" fit-margin-top="15" fit-margin-left="15" fit-margin-right="15" @@ -44,7 +44,9 @@ inkscape:snap-grids="true" showguides="false" inkscape:guide-bbox="true" - inkscape:snap-global="false"> + inkscape:snap-global="true" + inkscape:snap-bbox="true" + inkscape:object-paths="true"> + gradientTransform="matrix(0,51.373343,-57.331141,0,550.68376,27.989324)" /> - - + gradientTransform="matrix(51.373343,0,0,57.331141,1132.6473,647.37171)" /> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -5658,16 +5831,18 @@ inkscape:groupmode="layer" id="layer35" inkscape:label="background" - style="display:none"> + style="display:inline" + sodipodi:insensitive="true"> + inkscape:export-ydpi="300" + inkscape:export-filename="/home/laurent/Images/background.png" /> + style="display:inline" + sodipodi:insensitive="true"> + id="pwm"> + + + + + + + + + + - + style="font-size:22.39999962px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;font-family:Sans" + id="text9734"> + d="m 218.29909,148.86051 l 15.05,0 l 0,3.18282 l -5.41407,0 l 0,13.14687 l -4.21093,0 l 0,-13.14687 l -5.425,0 l 0,-3.18282" + id="path13625" + inkscape:connector-curvature="0" /> + + + + + + + + style="font-size:22.39999962px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#488eff;font-family:Sans" + id="text9734-2"> + d="m 276.62875,182.50113 c 0.88229,1e-5 1.51301,-0.16405 1.89219,-0.49219 c 0.38645,-0.32811 0.57968,-0.86769 0.57969,-1.61875 c -1e-5,-0.74373 -0.19324,-1.27602 -0.57969,-1.59687 c -0.37918,-0.32082 -1.0099,-0.48124 -1.89219,-0.48125 l -1.77187,0 l 0,4.18906 l 1.77187,0 m -1.77187,2.90938 l 0,6.17968 l -4.21094,0 l 0,-16.32968 l 6.43125,0 c 2.15103,1e-5 3.72603,0.36095 4.725,1.08281 c 1.00624,0.72189 1.50936,1.86303 1.50938,3.42344 c -2e-5,1.07917 -0.26252,1.96511 -0.7875,2.65781 c -0.51773,0.69272 -1.30158,1.20313 -2.35157,1.53125 c 0.57603,0.13126 1.09009,0.43022 1.54219,0.89687 c 0.45936,0.45939 0.92238,1.15939 1.38906,2.1 l 2.28594,4.6375 l -4.48437,0 l -1.99063,-4.05781 c -0.40105,-0.81666 -0.80938,-1.37447 -1.225,-1.67344 c -0.40834,-0.29895 -0.95522,-0.44843 -1.64062,-0.44843 l -1.19219,0" + id="path13616" + inkscape:connector-curvature="0" /> + d="m 293.53813,181.84488 c -0.86772,1e-5 -1.53126,0.31355 -1.99063,0.94063 c -0.45209,0.6198 -0.67813,1.51667 -0.67812,2.69062 c -10e-6,1.17397 0.22603,2.07449 0.67812,2.70156 c 0.45937,0.6198 1.12291,0.92969 1.99063,0.92969 c 0.85311,0 1.50572,-0.30989 1.95781,-0.92969 c 0.45207,-0.62707 0.67811,-1.52759 0.67813,-2.70156 c -2e-5,-1.17395 -0.22606,-2.07082 -0.67813,-2.69062 c -0.45209,-0.62708 -1.1047,-0.94062 -1.95781,-0.94063 m 0,-2.8 c 2.10728,1e-5 3.75155,0.56876 4.93281,1.70625 c 1.18853,1.13751 1.7828,2.71251 1.78281,4.725 c -1e-5,2.01251 -0.59428,3.5875 -1.78281,4.725 c -1.18126,1.1375 -2.82553,1.70625 -4.93281,1.70625 c -2.11459,0 -3.7698,-0.56875 -4.96563,-1.70625 c -1.18854,-1.1375 -1.78281,-2.71249 -1.78281,-4.725 c 0,-2.01249 0.59427,-3.58749 1.78281,-4.725 c 1.19583,-1.13749 2.85104,-1.70624 4.96563,-1.70625" + id="path13618" + inkscape:connector-curvature="0" /> + d="m 303.10844,174.57144 l 3.91562,0 l 0,17.01875 l -3.91562,0 l 0,-17.01875" + id="path13620" + inkscape:connector-curvature="0" /> + d="m 310.80844,174.57144 l 3.91562,0 l 0,17.01875 l -3.91562,0 l 0,-17.01875" + id="path13622" + inkscape:connector-curvature="0" /> + + + d="m 259.44596,202.46052 l 6.98906,0 c 2.07812,2e-5 3.67134,0.46304 4.77969,1.38906 c 1.11561,0.91877 1.67342,2.23126 1.67344,3.9375 c -2e-5,1.71355 -0.55783,3.03334 -1.67344,3.95938 c -1.10835,0.91875 -2.70157,1.37813 -4.77969,1.37812 l -2.77812,0 l 0,5.66563 l -4.21094,0 l 0,-16.32969 m 4.21094,3.05156 l 0,4.56094 l 2.32968,0 c 0.81666,10e-6 1.44739,-0.19687 1.89219,-0.59063 c 0.44478,-0.40103 0.66718,-0.96613 0.66719,-1.69531 c -10e-6,-0.72915 -0.22241,-1.29061 -0.66719,-1.68437 c -0.4448,-0.39374 -1.07553,-0.59061 -1.89219,-0.59063 l -2.32968,0" + id="path13605" + inkscape:connector-curvature="0" /> - Throttle - Roll - Pitch - Yaw - Flight Mode + d="m 275.67721,206.54021 l 3.91562,0 l 0,12.25 l -3.91562,0 l 0,-12.25 m 0,-4.76875 l 3.91562,0 l 0,3.19375 l -3.91562,0 l 0,-3.19375" + id="path13607" + inkscape:connector-curvature="0" /> + d="m 287.65377,203.06208 l 0,3.47813 l 4.03594,0 l 0,2.8 l -4.03594,0 l 0,5.19531 c 0,0.56875 0.11302,0.95521 0.33907,1.15937 c 0.22603,0.19688 0.67447,0.29532 1.34531,0.29532 l 2.0125,0 l 0,2.8 l -3.35781,0 c -1.54584,0 -2.64324,-0.32084 -3.29219,-0.9625 c -0.64167,-0.64896 -0.9625,-1.74635 -0.9625,-3.29219 l 0,-5.19531 l -1.94688,0 l 0,-2.8 l 1.94688,0 l 0,-3.47813 l 3.91562,0" + id="path13609" + inkscape:connector-curvature="0" /> + d="m 303.9944,206.92302 l 0,3.19375 c -0.53231,-0.36457 -1.06824,-0.63437 -1.60781,-0.80938 c -0.53231,-0.17499 -1.08647,-0.26249 -1.6625,-0.2625 c -1.09376,1e-5 -1.94689,0.32085 -2.55938,0.9625 c -0.60521,0.63439 -0.90782,1.52397 -0.90781,2.66875 c -10e-6,1.1448 0.3026,2.03803 0.90781,2.67969 c 0.61249,0.63438 1.46562,0.95157 2.55938,0.95156 c 0.61249,1e-5 1.19217,-0.0911 1.73906,-0.27343 c 0.55415,-0.18229 1.06457,-0.45208 1.53125,-0.80938 l 0,3.20469 c -0.61251,0.22604 -1.23595,0.39375 -1.87031,0.50312 c -0.6271,0.11667 -1.25783,0.175 -1.89219,0.175 c -2.20938,0 -3.93751,-0.5651 -5.18438,-1.69531 c -1.24687,-1.1375 -1.87031,-2.71614 -1.87031,-4.73594 c 0,-2.01978 0.62344,-3.59478 1.87031,-4.725 c 1.24687,-1.13748 2.975,-1.70623 5.18438,-1.70625 c 0.64166,2e-5 1.27238,0.0583 1.89219,0.175 c 0.62707,0.10939 1.2505,0.2771 1.87031,0.50313" + id="path13611" + inkscape:connector-curvature="0" /> + + + + + + + + + + + + + + + + + + @@ -5833,72 +6059,80 @@ inkscape:groupmode="layer" id="layer20" inkscape:label="ppm" - style="display:none"> + style="display:none" + sodipodi:insensitive="true"> + id="ppm"> + + + + + + - + style="font-size:22.39999962px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;font-family:Sans" + id="text9734-24"> - - + d="m 174.20226,166.62213 l 6.98906,0 c 2.07812,1e-5 3.67135,0.46303 4.77969,1.38906 c 1.11561,0.91876 1.67342,2.23126 1.67344,3.9375 c -2e-5,1.71355 -0.55783,3.03334 -1.67344,3.95937 c -1.10834,0.91876 -2.70157,1.37813 -4.77969,1.37813 l -2.77812,0 l 0,5.66562 l -4.21094,0 l 0,-16.32968 m 4.21094,3.05156 l 0,4.56094 l 2.32969,0 c 0.81665,0 1.44738,-0.19687 1.89218,-0.59063 c 0.44478,-0.40103 0.66718,-0.96614 0.66719,-1.69531 c -1e-5,-0.72916 -0.22241,-1.29061 -0.66719,-1.68438 c -0.4448,-0.39373 -1.07553,-0.59061 -1.89218,-0.59062 l -2.32969,0" + id="path13536" + inkscape:connector-curvature="0" /> + d="m 190.60851,166.62213 l 6.98906,0 c 2.07812,1e-5 3.67135,0.46303 4.77969,1.38906 c 1.11561,0.91876 1.67342,2.23126 1.67344,3.9375 c -2e-5,1.71355 -0.55783,3.03334 -1.67344,3.95937 c -1.10834,0.91876 -2.70157,1.37813 -4.77969,1.37813 l -2.77812,0 l 0,5.66562 l -4.21094,0 l 0,-16.32968 m 4.21094,3.05156 l 0,4.56094 l 2.32969,0 c 0.81665,0 1.44738,-0.19687 1.89218,-0.59063 c 0.44478,-0.40103 0.66718,-0.96614 0.66719,-1.69531 c -1e-5,-0.72916 -0.22241,-1.29061 -0.66719,-1.68438 c -0.4448,-0.39373 -1.07553,-0.59061 -1.89218,-0.59062 l -2.32969,0" + id="path13538" + inkscape:connector-curvature="0" /> + d="m 207.01476,166.62213 l 5.35938,0 l 3.71875,8.73906 l 3.74062,-8.73906 l 5.34844,0 l 0,16.32968 l -3.98125,0 l 0,-11.94375 l -3.7625,8.80469 l -2.66875,0 l -3.7625,-8.80469 l 0,11.94375 l -3.99219,0 l 0,-16.32968" + id="path13540" + inkscape:connector-curvature="0" /> - - PPM Signal - - + d="m 248.47882,167.13619 l 0,3.45625 c -0.89689,-0.40103 -1.77188,-0.70363 -2.625,-0.90781 c -0.85313,-0.20416 -1.65886,-0.30624 -2.41719,-0.30625 c -1.00625,1e-5 -1.75,0.13855 -2.23125,0.41562 c -0.48125,0.2771 -0.72188,0.7073 -0.72187,1.29063 c -1e-5,0.43751 0.16041,0.78021 0.48125,1.02812 c 0.32812,0.24064 0.91874,0.44845 1.77187,0.62344 l 1.79375,0.36094 c 1.81562,0.36459 3.10624,0.91875 3.87188,1.6625 c 0.76561,0.74375 1.14842,1.80104 1.14844,3.17187 c -2e-5,1.80105 -0.53595,3.14271 -1.60782,4.025 c -1.06459,0.875 -2.69428,1.3125 -4.88906,1.3125 c -1.03542,0 -2.07448,-0.0984 -3.11719,-0.29531 c -1.04271,-0.19688 -2.08541,-0.48854 -3.12812,-0.875 l 0,-3.55469 c 1.04271,0.55417 2.04895,0.97344 3.01875,1.25781 c 0.97708,0.27709 1.9177,0.41563 2.82187,0.41563 c 0.91875,0 1.62239,-0.15312 2.11094,-0.45938 c 0.48853,-0.30624 0.7328,-0.74374 0.73281,-1.3125 c -1e-5,-0.51041 -0.16771,-0.90416 -0.50312,-1.18125 c -0.32813,-0.27707 -0.98803,-0.52499 -1.97969,-0.74375 l -1.62969,-0.36093 c -1.63333,-0.35 -2.82917,-0.90781 -3.5875,-1.67344 c -0.75104,-0.76562 -1.12656,-1.79739 -1.12656,-3.09531 c 0,-1.62603 0.525,-2.87655 1.575,-3.75157 c 1.05,-0.87498 2.55937,-1.31248 4.52813,-1.3125 c 0.89686,2e-5 1.81926,0.0693 2.76718,0.20782 c 0.94791,0.13126 1.92864,0.33178 2.94219,0.60156" + id="path13542" + inkscape:connector-curvature="0" /> + + + + + @@ -5906,30 +6140,21 @@ inkscape:groupmode="layer" id="layer21" inkscape:label="sbus" - style="display:none"> + style="display:none" + sodipodi:insensitive="true"> - @@ -5940,25 +6165,39 @@ style="stroke-width:20.94064903;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none"> + style="fill:#cccccc;stroke:#1f4697" + sodipodi:nodetypes="cc" /> + style="fill:#cccccc;stroke:#ec6004" + sodipodi:nodetypes="cc" /> + style="fill:none;stroke:#d81900" + sodipodi:nodetypes="cc" /> + style="fill:#cccccc;stroke:#000000" + sodipodi:nodetypes="cc" /> + + style="display:none" + sodipodi:insensitive="true"> - + style="fill:#cccccc;stroke:#1f4697" + sodipodi:nodetypes="cc" /> + style="fill:#cccccc;stroke:#ec6004" + sodipodi:nodetypes="cc" /> + style="fill:none;stroke:#d81900" + sodipodi:nodetypes="cc" /> + style="fill:#cccccc;stroke:#000000" + sodipodi:nodetypes="cc" /> + Spectrum + x="1368.6637">Spectrum Satellite + + + + + + + + + + + + + inkscape:label="nano" + style="display:none" + sodipodi:insensitive="true"> + + - + transform="matrix(0,1,-1,0,2061.279,227.14185)" + id="g25232"> - - - - - + id="path8694-9" + d="m 399.52159,854.64741 c 0,1.17607 -0.97554,2.13057 -2.17755,2.13057 h -29.33588 c -1.202,0 -2.17754,-0.9545 -2.17754,-2.13057 l 2.17754,-1.42854 l -2.17754,-2.26372 v -33.02371 l 2.17754,-2.53004 l -2.17754,-1.37209 c 0,-1.17607 0.97554,-2.13056 2.17754,-2.13056 h 29.33697 c 1.202,0 2.17754,0.95449 2.17754,2.13056 v 40.6181 z" /> + style="fill:#5a5a5a" + id="rect8696-4" + height="3.9905427" + width="10.175666" + y="816.62433" + x="372.0007" /> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + id="g24786" + transform="matrix(0,1,-1,0,1204.9703,174.54121)"> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + x="500.91568" + y="681.94617" + width="28.597694" + height="15.61915" + id="rect8700-7" + style="fill:#c4c4c4;stroke:#6d6d6d;stroke-width:0.69141293" + rx="0.91714674" + ry="0.91714674" /> + cx="131.185" + cy="20.466" + r="1.413" + id="circle8702-2" + sodipodi:cx="131.185" + sodipodi:cy="20.466" + sodipodi:rx="1.413" + sodipodi:ry="1.413" + style="fill:#2c2c2c" + d="m 132.598,20.466 c 0,0.780378 -0.63262,1.413 -1.413,1.413 c -0.78038,0 -1.413,-0.632622 -1.413,-1.413 c 0,-0.780379 0.63262,-1.413 1.413,-1.413 c 0.78038,0 1.413,0.632621 1.413,1.413 z" /> + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + id="g8714-9" + transform="matrix(1.0887723,0,0,1.065281,431.17616,631.18026)"> + - - - - - - - - - + id="g8718-4" + transform="matrix(1.0887723,0,0,1.065281,431.17616,631.18026)"> + - - - - - - - - - - - - - - - - Nano - - - - - - - - - + id="g8722-8" + transform="matrix(1.0887723,0,0,1.065281,431.17616,631.18026)"> + - - - + id="g8726-5" + transform="matrix(1.0887723,0,0,1.065281,431.17616,631.18026)"> + - - - + id="g8730-3" + transform="matrix(1.0887723,0,0,1.065281,431.17616,631.18026)"> + - - - + id="g8734-8" + transform="matrix(1.0887723,0,0,1.065281,431.17616,631.18026)"> + - - - + id="g8738-2" + transform="matrix(1.0887723,0,0,1.065281,431.17616,631.18026)"> + - - - + id="g8742-5" + transform="matrix(1.0887723,0,0,1.065281,431.17616,631.18026)"> + - - - + id="g8746-8" + transform="matrix(1.0887723,0,0,1.065281,431.17616,631.18026)"> + - - - + id="g8750-5" + transform="matrix(1.0887723,0,0,1.065281,431.17616,631.18026)"> + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + id="g8754-0" + transform="matrix(1.0887723,0,0,1.065281,431.17616,631.18026)"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -13572,12 +14309,14 @@ inkscape:groupmode="layer" id="layer13" inkscape:label="multirotors-frames" - style="display:none"> + style="display:inline" + sodipodi:insensitive="true"> + style="opacity:0.6;fill:none;stroke:#ff0000;stroke-width:7.5;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;marker-start:url(#DotS);marker-end:url(#Arrow2Send)" /> + style="opacity:0.6;fill:none;stroke:#ff0000;stroke-width:7.5;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;marker-start:url(#DotS);marker-end:url(#Arrow2Send)" + sodipodi:nodetypes="ccc" /> + style="opacity:0.6;fill:none;stroke:#ff0000;stroke-width:7.5;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;marker-start:url(#DotS);marker-end:url(#Arrow2Send)" /> + style="opacity:0.6;fill:none;stroke:#ff0000;stroke-width:7.5;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;marker-start:url(#DotS);marker-end:url(#Arrow2Send)" /> @@ -17289,48 +18081,54 @@ inkscape:label="flying-wing" style="display:inline"> + id="elevon" + inkscape:export-filename="/home/laurent/Images/nano_rc_input.png" + inkscape:export-xdpi="300" + inkscape:export-ydpi="300"> + transform="translate(1.2734359,1.2734359)" + sodipodi:nodetypes="cccc" /> + transform="translate(1.2734359,1.2734359)" + sodipodi:nodetypes="cccc" /> + transform="translate(1.2734359,1.2734359)" + sodipodi:nodetypes="cccc" /> @@ -18046,7 +18844,7 @@ id="circle3808-0-9" /> @@ -18129,7 +18927,7 @@ id="aileron-top-body-1" d="m 362.386,1557.617 l -45.657,17.535 H 134.987 c 0,0 -19.025,-2.023 -17.592,45.59 c 1.433,47.611 4.344,44.581 17.592,50.531 h 227.87 l 23.964,171.965 h -71.977 c 0,0 -11.272,1.641 -11.22,23.54 c 0.052,21.898 11.221,23.909 11.221,23.909 h 167.501 c 0,0 10.984,-0.138 10.914,-22.313 c -0.068,-22.175 -7.01,-25.138 -10.773,-25.138 c -3.767,0 -71.672,0 -71.672,0 l 22.967,-171.966 h 228.867 c 0,0 17.592,5.289 17.592,-48.062 c 0,-53.352 -17.592,-48.061 -17.592,-48.061 H 480.907 l -45.656,-17.535 c 0,0 -8.607,-68.509 -9.641,-75.511 c 0,0 -5.703,-10.831 -15.738,-10.831 c -10.036,0 -24.542,-0.279 -24.274,0 c 0.269,0.276 -12.383,2.728 -13.571,10.831 c -1.188,8.105 -9.641,75.516 -9.641,75.516 z" inkscape:connector-curvature="0" - style="fill:#010101" /> + style="fill:#3c3c3c;fill-opacity:1" /> @@ -19405,7 +20203,7 @@ style="fill:#010101" /> @@ -20642,7 +21440,7 @@ image/svg+xml - - -image/svg+xml6 - - - - -4 - - - - -4 - + + +image/svg+xml6 + + + + +4 + + + + +4 + \ No newline at end of file From 4695a60df69fc9fcee9521e58b21d8c18f558610 Mon Sep 17 00:00:00 2001 From: m_thread Date: Sun, 31 Aug 2014 14:35:45 +0200 Subject: [PATCH 095/203] OP-1222 Added base page for selection kind of action. --- .../setupwizard/pages/subvehiclepage.cpp | 190 ++++++++++++++++++ .../setupwizard/pages/subvehiclepage.h | 66 ++++++ .../setupwizard/pages/subvehiclepage.ui | 164 +++++++++++++++ .../src/plugins/setupwizard/setupwizard.pro | 9 +- 4 files changed, 426 insertions(+), 3 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.ui diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.cpp new file mode 100644 index 000000000..9b128efbf --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.cpp @@ -0,0 +1,190 @@ +/** + ****************************************************************************** + * + * @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 "subvehiclepage.h" +#include "ui_subvehiclepage.h" +#include "setupwizard.h" + +SubVehiclePage::SubVehiclePage(SetupWizard *wizard, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::SubVehiclePage) +{ + ui->setupUi(this); + + m_renderer = new QSvgRenderer(); + m_renderer->load(QString(":/configgadget/images/multirotor-shapes.svg")); + m_multiPic = new QGraphicsSvgItem(); + m_multiPic->setSharedRenderer(m_renderer); + QGraphicsScene *scene = new QGraphicsScene(this); + scene->addItem(m_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())); + ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect()); + ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio); +} + +SubVehiclePage::~SubVehiclePage() +{ + delete ui; +} + +void SubVehiclePage::initializePage() +{ + updateAvailableTypes(); + updateImageAndDescription(); +} + +bool SubVehiclePage::validatePage() +{ + SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE)ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); + + getWizard()->setVehicleSubType(type); + return true; +} + +void SubVehiclePage::resizeEvent(QResizeEvent *event) +{ + Q_UNUSED(event); + if (m_multiPic) { + ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect()); + ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio); + } +} + +void SubVehiclePage::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 X"), SetupWizard::MULTI_ROTOR_HEXA_X); + m_descriptions << tr("Hexacopter X"); + + ui->typeCombo->addItem(tr("Hexacopter H"), SetupWizard::MULTI_ROTOR_HEXA_H); + m_descriptions << tr("Hexacopter H"); + + ui->typeCombo->addItem(tr("Hexacopter Coax (Y6)"), SetupWizard::MULTI_ROTOR_HEXA_COAX_Y); + m_descriptions << tr("Hexacopter Coax (Y6)"); + + + // 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 SubVehiclePage::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 SubVehiclePage::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_HEXA_X: + elementId = "quad-hexa-X"; + 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; + } + m_multiPic->setElementId(elementId); + ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect()); + ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio); + + ui->typeDescription->setText(description); +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.h new file mode 100644 index 000000000..3ee42766a --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.h @@ -0,0 +1,66 @@ +/** + ****************************************************************************** + * + * @file subvehiclepage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. + * @addtogroup + * @{ + * @addtogroup SubVehiclePage + * @{ + * @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 SUBVEHICLEPAGEPAGE_H +#define SUBVEHICLEPAGEPAGE_H + +#include +#include +#include + +#include "abstractwizardpage.h" + +namespace Ui { +class SubVehiclePage; +} + +class SubVehiclePage : public AbstractWizardPage { + Q_OBJECT + +public: + explicit SubVehiclePage(SetupWizard *wizard, QWidget *parent = 0); + ~SubVehiclePage(); + + void initializePage(); + bool validatePage(); + +protected: + void resizeEvent(QResizeEvent *event); + +private: + Ui::SubVehiclePage *ui; + void setupMultiTypesCombo(); + QSvgRenderer* m_renderer; + QGraphicsSvgItem *m_multiPic; + void updateAvailableTypes(); + QList m_descriptions; + +private slots: + void updateImageAndDescription(); +}; + +#endif // SUBVEHICLEPAGEPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.ui new file mode 100644 index 000000000..9f6ea3219 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.ui @@ -0,0 +1,164 @@ + + + SubVehiclePage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + + <!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: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> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + + 4 + + + + + + + 4 + + + + + + 125 + 36 + + + + + 10 + 50 + false + + + + Multirotor type: + + + + + + + + 125 + 20 + + + + + + + + + + + 0 + 0 + + + + Qt::ScrollBarAlwaysOn + + + Qt::ScrollBarAlwaysOff + + + Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse + + + + + + + + + + 0 + 0 + + + + + 200 + 200 + + + + true + + + QFrame::NoFrame + + + 0 + + + 0 + + + Qt::ScrollBarAlwaysOff + + + Qt::ScrollBarAlwaysOff + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + false + + + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index d415c374a..0dc55fe77 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -37,7 +37,8 @@ HEADERS += setupwizardplugin.h \ pages/biascalibrationpage.h \ pages/airframestabfixedwingpage.h \ pages/escpage.h \ - pages/servopage.h + pages/servopage.h \ + pages/subvehiclepage.h SOURCES += setupwizardplugin.cpp \ setupwizard.cpp \ @@ -66,7 +67,8 @@ SOURCES += setupwizardplugin.cpp \ pages/biascalibrationpage.cpp \ pages/airframestabfixedwingpage.cpp \ pages/escpage.cpp \ - pages/servopage.cpp + pages/servopage.cpp \ + pages/subvehiclepage.cpp OTHER_FILES += SetupWizard.pluginspec @@ -91,7 +93,8 @@ FORMS += \ pages/biascalibrationpage.ui \ pages/airframestabfixedwingpage.ui \ pages/escpage.ui \ - pages/servopage.ui + pages/servopage.ui \ + pages/subvehiclepage.ui RESOURCES += \ wizardResources.qrc From 798defd12d6da38c922674ba74a5f169db7f52ad Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sun, 31 Aug 2014 20:15:01 +0200 Subject: [PATCH 096/203] OP-1222 uncrustify --- .../configfixedwingwidget.cpp | 1 - .../cfg_vehicletypes/configfixedwingwidget.h | 1 - .../src/plugins/welcome/welcomemode.cpp | 21 +++++++------------ .../src/plugins/welcome/welcomemode.h | 7 +++---- 4 files changed, 11 insertions(+), 19 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 887bf5fdf..5a0069de1 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -176,7 +176,6 @@ void ConfigFixedWingWidget::setupUI(QString frameType) scene->setSceneRect(planeimg->boundingRect()); m_aircraft->planeShape->fitInView(planeimg, Qt::KeepAspectRatio); m_aircraft->planeShape->setScene(scene); - } void ConfigFixedWingWidget::registerWidgets(ConfigTaskWidget &parent) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index e4bc8f115..7955e7b9c 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -71,7 +71,6 @@ protected: private slots: virtual void setupUI(QString airframeType); virtual bool throwConfigError(QString airframeType); - }; #endif // CONFIGFIXEDWINGWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp b/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp index 090a77d85..a451e2115 100644 --- a/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp +++ b/ground/openpilotgcs/src/plugins/welcome/welcomemode.cpp @@ -80,20 +80,17 @@ WelcomeMode::WelcomeMode() : m_d->quickView->setSource(QUrl("qrc:/welcome/qml/main.qml")); m_container = NULL; - QNetworkAccessManager* networkAccessManager = new QNetworkAccessManager; + QNetworkAccessManager *networkAccessManager = new QNetworkAccessManager; // Only attempt to request our version info if the network is accessible - if(networkAccessManager->networkAccessible() == QNetworkAccessManager::Accessible) - { - connect(networkAccessManager, SIGNAL(finished(QNetworkReply*)), this, SLOT(networkResponseReady(QNetworkReply*))); + if (networkAccessManager->networkAccessible() == QNetworkAccessManager::Accessible) { + connect(networkAccessManager, SIGNAL(finished(QNetworkReply *)), this, SLOT(networkResponseReady(QNetworkReply *))); // This will delete the network access manager instance when we're done - connect(networkAccessManager, SIGNAL(finished(QNetworkReply*)), networkAccessManager, SLOT(deleteLater())); + connect(networkAccessManager, SIGNAL(finished(QNetworkReply *)), networkAccessManager, SLOT(deleteLater())); networkAccessManager->get(QNetworkRequest(QUrl("http://www.openpilot.org/opver"))); - } - else - { + } else { // No network, can delete this now as we don't need it. delete networkAccessManager; } @@ -158,17 +155,15 @@ void WelcomeMode::triggerAction(const QString &actionId) Core::ModeManager::instance()->triggerAction(actionId); } -void WelcomeMode::networkResponseReady(QNetworkReply* reply) +void WelcomeMode::networkResponseReady(QNetworkReply *reply) { - if(reply != NULL) - { + if (reply != NULL) { QString version(reply->readAll()); version = version.trimmed(); reply->deleteLater(); - if(version != VersionInfo::tagOrHash8()) - { + if (version != VersionInfo::tagOrHash8()) { m_newVersionText = tr("(Update Available: %1)").arg(version); emit newVersionTextChanged(); } diff --git a/ground/openpilotgcs/src/plugins/welcome/welcomemode.h b/ground/openpilotgcs/src/plugins/welcome/welcomemode.h index ab85912b9..a51cf3909 100644 --- a/ground/openpilotgcs/src/plugins/welcome/welcomemode.h +++ b/ground/openpilotgcs/src/plugins/welcome/welcomemode.h @@ -45,8 +45,7 @@ namespace Welcome { struct WelcomeModePrivate; class WELCOME_EXPORT WelcomeMode : public Core::IMode { - Q_OBJECT - Q_PROPERTY(QString versionString READ versionString) + Q_OBJECT Q_PROPERTY(QString versionString READ versionString) Q_PROPERTY(QString newVersionText READ newVersionText NOTIFY newVersionTextChanged) public: @@ -92,8 +91,8 @@ private: int m_priority; QString m_newVersionText; - private slots: - void networkResponseReady(QNetworkReply* reply); +private slots: + void networkResponseReady(QNetworkReply *reply); }; } // namespace Welcome From 3f9fa97d0f435fd3e5e4e825d4d07c073eb317bc Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sun, 31 Aug 2014 19:34:51 +0200 Subject: [PATCH 097/203] OP-1222 fixed FW elevon wizzard channel assignment to be compatible with config widget --- .../src/plugins/setupwizard/vehicleconfigurationhelper.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index f609379f6..c32c4c3e6 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -1649,8 +1649,8 @@ void VehicleConfigurationHelper::setupElevon() channels[1].yaw = 0; guiSettings.fixedwing.FixedWingThrottle = 3; - guiSettings.fixedwing.FixedWingPitch1 = 1; - guiSettings.fixedwing.FixedWingPitch2 = 2; + guiSettings.fixedwing.FixedWingRoll1 = 1; + guiSettings.fixedwing.FixedWingRoll2 = 2; applyMixerConfiguration(channels); applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON, guiSettings); From daefab99be188b8412c4e15aa4efa0129e85f754 Mon Sep 17 00:00:00 2001 From: Corvus Corax Date: Sun, 31 Aug 2014 20:11:53 +0200 Subject: [PATCH 098/203] OP-1222 fixed elevon mixer to be consistent with aileron type (no channel reversals needed), made FW wizzard and config widget create the same type of mixer setup --- .../config/cfg_vehicletypes/configfixedwingwidget.cpp | 6 +++--- .../src/plugins/setupwizard/vehicleconfigurationhelper.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 5a0069de1..14df42f0c 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -427,7 +427,7 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) if (channel > -1) { setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); value = (double)(m_aircraft->elevonSlider2->value() * 1.27); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, -value); value = (double)(m_aircraft->elevonSlider1->value() * 1.27); setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, value); @@ -436,7 +436,7 @@ bool ConfigFixedWingWidget::setupFrameElevon(QString airframeType) value = (double)(m_aircraft->elevonSlider2->value() * 1.27); setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_PITCH, value); value = (double)(m_aircraft->elevonSlider1->value() * 1.27); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -value); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, value); } m_aircraft->fwStatusLabel->setText("Mixer generated"); @@ -498,7 +498,7 @@ bool ConfigFixedWingWidget::setupFrameVtail(QString airframeType) channel = m_aircraft->fwAileron2ChannelBox->currentIndex() - 1; setMixerType(mixer, channel, VehicleConfig::MIXERTYPE_SERVO); - setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, -127); + setMixerVectorValue(mixer, channel, VehicleConfig::MIXERVECTOR_ROLL, 127); } // vtail diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index c32c4c3e6..0e37d5128 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -1636,8 +1636,8 @@ void VehicleConfigurationHelper::setupElevon() channels[0].type = MIXER_TYPE_SERVO; channels[0].throttle1 = 0; channels[0].throttle2 = 0; - channels[0].roll = -100; - channels[0].pitch = 100; + channels[0].roll = 100; + channels[0].pitch = -100; channels[0].yaw = 0; // Elevon Servo 1 (Chan 2) @@ -1645,7 +1645,7 @@ void VehicleConfigurationHelper::setupElevon() channels[1].throttle1 = 0; channels[1].throttle2 = 0; channels[1].roll = 100; - channels[1].pitch = -100; + channels[1].pitch = 100; channels[1].yaw = 0; guiSettings.fixedwing.FixedWingThrottle = 3; From c56980e54ec365f93434c7f6a82d8910c0e95223 Mon Sep 17 00:00:00 2001 From: m_thread Date: Tue, 2 Sep 2014 00:10:31 +0200 Subject: [PATCH 099/203] OP-1222 Re-factored and renamed selection page. --- .../setupwizard/pages/selectionpage.cpp | 119 +++++++++++ .../{subvehiclepage.h => selectionpage.h} | 52 ++++- .../{subvehiclepage.ui => selectionpage.ui} | 58 +++--- .../setupwizard/pages/subvehiclepage.cpp | 190 ------------------ .../src/plugins/setupwizard/setupwizard.pro | 6 +- 5 files changed, 194 insertions(+), 231 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp rename ground/openpilotgcs/src/plugins/setupwizard/pages/{subvehiclepage.h => selectionpage.h} (54%) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{subvehiclepage.ui => selectionpage.ui} (59%) delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.cpp diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp new file mode 100644 index 000000000..a296d2521 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp @@ -0,0 +1,119 @@ +/** + ****************************************************************************** + * + * @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 "selectionpage.h" +#include "ui_selectionpage.h" +#include "setupwizard.h" + +SelectionPage::SelectionPage(SetupWizard *wizard, QString shapeFile, QWidget *parent) : + AbstractWizardPage(wizard, parent), + ui(new Ui::SelectionPage) +{ + ui->setupUi(this); + + QSvgRenderer *renderer = new QSvgRenderer(); + renderer->load(shapeFile); + m_shape = new QGraphicsSvgItem(); + m_shape->setSharedRenderer(renderer); + QGraphicsScene *scene = new QGraphicsScene(this); + scene->addItem(m_shape); + ui->typeGraphicsView->setScene(scene); + + connect(ui->typeCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(selectionChanged(int))); +} + +SelectionPage::~SelectionPage() +{ + while (!m_selectionItems.empty()) { + delete m_selectionItems.takeFirst(); + } + delete ui; +} + +void SelectionPage::initializePage() +{ + //lazy init + if (m_selectionItems.isEmpty()) { + setupSelection(this); + foreach (SelectionItem * item, m_selectionItems) { + ui->typeCombo->addItem(item->name()); + } + + // Default to first item if any + if (ui->typeCombo->count() > 0) { + ui->typeCombo->setCurrentIndex(1); + } + } +} + +bool SelectionPage::validatePage() +{ + return validatePage(m_selectionItems.at(ui->typeCombo->currentIndex())); +} + +void SelectionPage::fitImage() +{ + if (m_shape) { + ui->typeGraphicsView->setSceneRect(m_shape->boundingRect()); + ui->typeGraphicsView->fitInView(m_shape, Qt::KeepAspectRatio); + } +} + +void SelectionPage::resizeEvent(QResizeEvent *event) +{ + Q_UNUSED(event); + fitImage(); +} + +void SelectionPage::showEvent(QShowEvent *event) +{ + Q_UNUSED(event); + fitImage(); +} + +void SelectionPage::selectionChanged(int index) +{ + SelectionItem *item = m_selectionItems.at(index); + m_shape->setElementId(item->shapeId()); + ui->typeDescription->setText(item->description()); + fitImage(); +} + +void SelectionPage::addItem(QString name, QString description, QString shapeId, int id) +{ + m_selectionItems << new SelectionItem(name, description, shapeId, id); +} + +void SelectionPage::setTitleLabel(QString text) +{ + ui->label->setText(text); +} + +SelectionItem::SelectionItem(QString name, QString description, QString shapeId, int id) : + m_name(name), m_description(description), m_shapeId(shapeId), m_id(id) +{ +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h similarity index 54% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.h rename to ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h index 3ee42766a..a3b0d2dd7 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h @@ -35,32 +35,62 @@ #include "abstractwizardpage.h" namespace Ui { -class SubVehiclePage; +class SelectionPage; } -class SubVehiclePage : public AbstractWizardPage { +class SelectionItem : public QObject { + Q_OBJECT +public: + SelectionItem(QString name, QString description, QString shapeId, int id); + ~SelectionItem(); + + QString name() { return m_name; } + QString description() { return m_description; } + QString shapeId() { return m_shapeId; } + int id() { return m_id; } + +private: + QString m_name; + QString m_description; + QString m_shapeId; + int m_id; +}; + +class Selection { +public: + virtual void addItem(QString name, QString description, QString shapeId, int id) = 0; + virtual void setTitleLabel(QString text) = 0; +}; + +class SelectionPage : public AbstractWizardPage, Selection { Q_OBJECT public: - explicit SubVehiclePage(SetupWizard *wizard, QWidget *parent = 0); - ~SubVehiclePage(); + explicit SelectionPage(SetupWizard *wizard, QString shapeFile, QWidget *parent = 0); + ~SelectionPage(); void initializePage(); bool validatePage(); + void addItem(QString name, QString description, QString shapeId, int id); + void setTitleLabel(QString text); + + virtual void setupSelection(Selection *selection) = 0; + virtual bool validatePage(SelectionItem *selectedItem) = 0; protected: void resizeEvent(QResizeEvent *event); + void showEvent(QShowEvent * event); private: - Ui::SubVehiclePage *ui; - void setupMultiTypesCombo(); - QSvgRenderer* m_renderer; - QGraphicsSvgItem *m_multiPic; - void updateAvailableTypes(); - QList m_descriptions; + Ui::SelectionPage *ui; + QGraphicsSvgItem *m_shape; + QList m_selectionItems; private slots: - void updateImageAndDescription(); + void selectionChanged(int index); + void fitImage(); + + }; #endif // SUBVEHICLEPAGEPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.ui similarity index 59% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.ui rename to ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.ui index 9f6ea3219..b86e9d4ac 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.ui @@ -1,7 +1,7 @@ - SubVehiclePage - + SelectionPage + 0 @@ -17,15 +17,7 @@ - <!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: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> + placeholder_text Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop @@ -37,23 +29,32 @@ p, li { white-space: pre-wrap; } + + 9 + - 4 + 0 + + 9 + + + 9 + - 4 + 0 - - - 125 - 36 - + + + 0 + 0 + @@ -63,17 +64,17 @@ p, li { white-space: pre-wrap; } - Multirotor type: + Select: - - - 125 - 20 - + + + 0 + 0 + @@ -82,13 +83,13 @@ p, li { white-space: pre-wrap; } - + 0 0 - Qt::ScrollBarAlwaysOn + Qt::ScrollBarAsNeeded Qt::ScrollBarAlwaysOff @@ -118,7 +119,10 @@ p, li { white-space: pre-wrap; } true - QFrame::NoFrame + QFrame::StyledPanel + + + QFrame::Plain 0 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.cpp deleted file mode 100644 index 9b128efbf..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/subvehiclepage.cpp +++ /dev/null @@ -1,190 +0,0 @@ -/** - ****************************************************************************** - * - * @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 "subvehiclepage.h" -#include "ui_subvehiclepage.h" -#include "setupwizard.h" - -SubVehiclePage::SubVehiclePage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), - ui(new Ui::SubVehiclePage) -{ - ui->setupUi(this); - - m_renderer = new QSvgRenderer(); - m_renderer->load(QString(":/configgadget/images/multirotor-shapes.svg")); - m_multiPic = new QGraphicsSvgItem(); - m_multiPic->setSharedRenderer(m_renderer); - QGraphicsScene *scene = new QGraphicsScene(this); - scene->addItem(m_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())); - ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect()); - ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio); -} - -SubVehiclePage::~SubVehiclePage() -{ - delete ui; -} - -void SubVehiclePage::initializePage() -{ - updateAvailableTypes(); - updateImageAndDescription(); -} - -bool SubVehiclePage::validatePage() -{ - SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE)ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); - - getWizard()->setVehicleSubType(type); - return true; -} - -void SubVehiclePage::resizeEvent(QResizeEvent *event) -{ - Q_UNUSED(event); - if (m_multiPic) { - ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect()); - ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio); - } -} - -void SubVehiclePage::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 X"), SetupWizard::MULTI_ROTOR_HEXA_X); - m_descriptions << tr("Hexacopter X"); - - ui->typeCombo->addItem(tr("Hexacopter H"), SetupWizard::MULTI_ROTOR_HEXA_H); - m_descriptions << tr("Hexacopter H"); - - ui->typeCombo->addItem(tr("Hexacopter Coax (Y6)"), SetupWizard::MULTI_ROTOR_HEXA_COAX_Y); - m_descriptions << tr("Hexacopter Coax (Y6)"); - - - // 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 SubVehiclePage::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 SubVehiclePage::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_HEXA_X: - elementId = "quad-hexa-X"; - 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; - } - m_multiPic->setElementId(elementId); - ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect()); - ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio); - - ui->typeDescription->setText(description); -} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index 0dc55fe77..d41e58eae 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -38,7 +38,7 @@ HEADERS += setupwizardplugin.h \ pages/airframestabfixedwingpage.h \ pages/escpage.h \ pages/servopage.h \ - pages/subvehiclepage.h + pages/selectionpage.h SOURCES += setupwizardplugin.cpp \ setupwizard.cpp \ @@ -68,7 +68,7 @@ SOURCES += setupwizardplugin.cpp \ pages/airframestabfixedwingpage.cpp \ pages/escpage.cpp \ pages/servopage.cpp \ - pages/subvehiclepage.cpp + pages/selectionpage.cpp OTHER_FILES += SetupWizard.pluginspec @@ -94,7 +94,7 @@ FORMS += \ pages/airframestabfixedwingpage.ui \ pages/escpage.ui \ pages/servopage.ui \ - pages/subvehiclepage.ui + pages/selectionpage.ui RESOURCES += \ wizardResources.qrc From f21a31cdbe697c0366612b19db610680f5ce3fbb Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 2 Sep 2014 12:31:19 +1000 Subject: [PATCH 100/203] Comment out destructor to fix compile --- .../openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h index a3b0d2dd7..1c274cfed 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h @@ -42,7 +42,7 @@ class SelectionItem : public QObject { Q_OBJECT public: SelectionItem(QString name, QString description, QString shapeId, int id); - ~SelectionItem(); +// ~SelectionItem(); QString name() { return m_name; } QString description() { return m_description; } From 34d8ba608c1fdfdf239fe4d2b0f3322b63dd1e83 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 2 Sep 2014 13:30:22 +1000 Subject: [PATCH 101/203] Change button order in wizard to match the order of the config plugin, also has two currently support types of airframe first --- .../plugins/setupwizard/pages/vehiclepage.ui | 88 +++++++++---------- 1 file changed, 44 insertions(+), 44 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui index 805659ebc..847ab657f 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/vehiclepage.ui @@ -99,50 +99,6 @@ p, li { white-space: pre-wrap; } - - - - false - - - - 10 - - - - CCPM Helicopters - - - QToolButton { border: none } - - - Helicopter - - - - :/setupwizard/resources/bttn-heli-up.png - :/setupwizard/resources/bttn-heli-down.png:/setupwizard/resources/bttn-heli-up.png - - - - 100 - 100 - - - - true - - - true - - - Qt::ToolButtonTextUnderIcon - - - true - - - @@ -190,6 +146,50 @@ p, li { white-space: pre-wrap; } + + + + false + + + + 10 + + + + CCPM Helicopters + + + QToolButton { border: none } + + + Helicopter + + + + :/setupwizard/resources/bttn-heli-up.png + :/setupwizard/resources/bttn-heli-down.png:/setupwizard/resources/bttn-heli-up.png + + + + 100 + 100 + + + + true + + + true + + + Qt::ToolButtonTextUnderIcon + + + true + + + From 7486ba88031528d160e618a78522ed466e1d808f Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 2 Sep 2014 14:23:26 +1000 Subject: [PATCH 102/203] Put channels in order, make outputs match the diagrams, channels now reflect common fixed wing model conventions --- .../plugins/setupwizard/pages/outputcalibrationpage.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 41f92770e..338bba122 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -174,9 +174,9 @@ void OutputCalibrationPage::setupVehicle() case SetupWizard::FIXED_WING_DUAL_AILERON: loadSVGFile(FIXEDWING_SVG_FILE); m_wizardIndexes << 0 << 1 << 2 << 2 << 2 << 2; - m_vehicleElementIds << "aileron" << "aileron-frame" << "aileron-motor" << "aileron-ail-left" << "aileron-ail-right" << "aileron-rudder" << "aileron-elevator"; + m_vehicleElementIds << "aileron" << "aileron-frame" << "aileron-motor" << "aileron-ail-left" << "aileron-ail-right" << "aileron-elevator" << "aileron-rudder"; m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5; - m_channelIndex << 0 << 2 << 0 << 1 << 3 << 4; + m_channelIndex << 0 << 2 << 0 << 5 << 1 << 3; setupActuatorMinMaxAndNeutral(2, 2, 5); @@ -185,9 +185,9 @@ void OutputCalibrationPage::setupVehicle() case SetupWizard::FIXED_WING_AILERON: loadSVGFile(FIXEDWING_SVG_FILE); m_wizardIndexes << 0 << 1 << 2 << 2 << 2; - m_vehicleElementIds << "aileron-single" << "ail2-frame" << "ail2-motor" << "ail2-aileron" << "ail2-rudder" << "ail2-elevator"; + m_vehicleElementIds << "aileron-single" << "ail2-frame" << "ail2-motor" << "ail2-aileron" << "ail2-elevator" << "ail2-rudder"; m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4; - m_channelIndex << 0 << 2 << 0 << 4 << 1; + m_channelIndex << 0 << 2 << 0 << 1 << 3; setupActuatorMinMaxAndNeutral(2, 2, 4); From 11068197c5bfafab1db8471570aa3506cddad95e Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 2 Sep 2014 14:29:49 +1000 Subject: [PATCH 103/203] Change motor for engine --- .../src/plugins/setupwizard/pages/outputcalibrationpage.ui | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui index fb56f4fb1..13e545ac8 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.ui @@ -91,7 +91,7 @@ p, li { white-space: pre-wrap; } - <html><head/><body><p>In this step we will set the neutral rate for the motor highlighted in the illustration to the right. <br/>Please pay attention to the details and in particular the motors position and its rotation direction. Ensure the motors are spinning in the correct direction as shown in the diagram. Swap any 2 motor wires to change the direction of a motor. </p><p>To find <span style=" font-weight:600;">the neutral rate for this engine</span>, press the Start button below and slide the slider to the right until the engine just starts to spin stable. <br/><br/>When done press button again to stop.</p></body></html> + <html><head/><body><p>In this step we will set the neutral rate for the motor highlighted in the illustration to the right. <br/>Please pay attention to the details and in particular the motors position and its rotation direction. Ensure the motors are spinning in the correct direction as shown in the diagram. Swap any 2 motor wires to change the direction of a motor. </p><p>To find <span style=" font-weight:600;">the neutral rate for this motor</span>, press the Start button below and slide the slider to the right until the motor just starts to spin stable. <br/><br/>When done press button again to stop.</p></body></html> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop From 819e4d6b3bc1ceffce7a8ea1e9a6c86317a6f09a Mon Sep 17 00:00:00 2001 From: m_thread Date: Tue, 2 Sep 2014 11:03:52 +0200 Subject: [PATCH 104/203] OP-1222 Finished re-factoring vehicle selection pages, --- .../setupwizard/pages/fixedwingpage.cpp | 114 +++------- .../plugins/setupwizard/pages/fixedwingpage.h | 32 +-- .../setupwizard/pages/fixedwingpage.ui | 170 --------------- .../plugins/setupwizard/pages/multipage.cpp | 196 +++++------------- .../src/plugins/setupwizard/pages/multipage.h | 32 +-- .../plugins/setupwizard/pages/multipage.ui | 164 --------------- .../setupwizard/pages/selectionpage.cpp | 15 +- .../plugins/setupwizard/pages/selectionpage.h | 14 +- .../setupwizard/pages/selectionpage.ui | 34 ++- .../src/plugins/setupwizard/setupwizard.pro | 2 - 10 files changed, 132 insertions(+), 641 deletions(-) delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index 3574887d8..1a2006c22 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -26,106 +26,46 @@ */ #include "fixedwingpage.h" -#include "ui_fixedwingpage.h" #include "setupwizard.h" FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), - ui(new Ui::FixedWingPage) + SelectionPage(wizard, QString(":/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg"), parent) { - ui->setupUi(this); - QSvgRenderer *renderer = new QSvgRenderer(); - renderer->load(QString(":/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg")); - m_fixedwingPic = new QGraphicsSvgItem(); - m_fixedwingPic->setSharedRenderer(renderer); - QGraphicsScene *scene = new QGraphicsScene(this); - scene->addItem(m_fixedwingPic); - ui->typeGraphicsView->setScene(scene); - - setupFixedWingTypesCombo(); - - // Default to Aileron setup - connect(ui->typeCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateImageAndDescription())); - ui->typeCombo->setCurrentIndex(0); } FixedWingPage::~FixedWingPage() { - delete ui; } -void FixedWingPage::initializePage() +bool FixedWingPage::validatePage(SelectionItem *seletedItem) { - updateAvailableTypes(); - updateImageAndDescription(); -} - -bool FixedWingPage::validatePage() -{ - SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE)ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); - - getWizard()->setVehicleSubType(type); + getWizard()->setVehicleSubType((SetupWizard::VEHICLE_SUB_TYPE)seletedItem->id()); return true; } -void FixedWingPage::fitInView() +void FixedWingPage::setupSelection(Selection *selection) { - if (m_fixedwingPic) { - ui->typeGraphicsView->setSceneRect(m_fixedwingPic->boundingRect()); - ui->typeGraphicsView->fitInView(m_fixedwingPic, Qt::KeepAspectRatio); - } -} - -void FixedWingPage::resizeEvent(QResizeEvent *event) -{ - Q_UNUSED(event); - fitInView(); -} - -void FixedWingPage::showEvent(QShowEvent *event) -{ - Q_UNUSED(event); - fitInView(); -} - -void FixedWingPage::setupFixedWingTypesCombo() -{ - ui->typeCombo->addItem(tr("Aileron Dual Servos"), SetupWizard::FIXED_WING_DUAL_AILERON); - m_descriptions << tr("This setup expects a traditional airframe using two independent aileron servos on their own channel (not connected by Y adapter) plus an elevator and a rudder. "); - - ui->typeCombo->addItem(tr("Aileron Single Servo"), SetupWizard::FIXED_WING_AILERON); - m_descriptions << tr("This setup expects a traditional airframe using a single alieron servo or two servos connected by a Y adapter plus an elevator and a rudder. "); - - ui->typeCombo->addItem(tr("Elevon"), SetupWizard::FIXED_WING_ELEVON); - m_descriptions << tr("This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet supported. Setup should include only two elevons, and should explicitly not include a rudder."); -} - -void FixedWingPage::updateAvailableTypes() -{} - -void FixedWingPage::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::FIXED_WING_DUAL_AILERON: - elementId = "aileron"; - break; - case SetupWizard::FIXED_WING_AILERON: - elementId = "aileron-single"; - break; - case SetupWizard::FIXED_WING_ELEVON: - elementId = "elevon"; - break; - default: - elementId = ""; - break; - } - m_fixedwingPic->setElementId(elementId); - ui->typeGraphicsView->setSceneRect(m_fixedwingPic->boundingRect()); - ui->typeGraphicsView->fitInView(m_fixedwingPic, Qt::KeepAspectRatio); - - ui->typeDescription->setText(description); + selection->setTitle(tr("OpenPilot Fixed-wing Configuration")); + selection->setText(tr("This part of the wizard will set up the OpenPilot controller for use with a fixed-wing " + "flying aircraft utilizing servos. The wizard supports the most common types of fixed-wing " + "aircraft, other variants of fixed-wing aircraft can be configured by using custom " + "configuration options in the Configuration plugin in the GCS.\n\n" + "Please select the type of fixed-wing you want to create a configuration for below:")); + selection->addItem(tr("Aileron Dual Servos"), + tr("This setup expects a traditional airframe using two independent aileron servos " + "on their own channel (not connected by Y adapter) plus an elevator and a rudder."), + "aileron", + SetupWizard::FIXED_WING_DUAL_AILERON); + + selection->addItem(tr("Aileron Single Servo"), + tr("This setup expects a traditional airframe using a single alieron servo or two servos " + "connected by a Y adapter plus an elevator and a rudder."), + "aileron-single", + SetupWizard::FIXED_WING_AILERON); + + selection->addItem(tr("Elevon"), + tr("This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet " + "supported. Setup should include only two elevons, and should explicitly not include a rudder."), + "elevon", + SetupWizard::FIXED_WING_ELEVON); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h index e74d91f67..8bd02f0e5 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h @@ -28,40 +28,18 @@ #ifndef FIXEDWINGPAGE_H #define FIXEDWINGPAGE_H -#include -#include -#include +#include "selectionpage.h" -#include "abstractwizardpage.h" - -namespace Ui { -class FixedWingPage; -} - -class FixedWingPage : public AbstractWizardPage { +class FixedWingPage : public SelectionPage { Q_OBJECT public: explicit FixedWingPage(SetupWizard *wizard, QWidget *parent = 0); ~FixedWingPage(); - void initializePage(); - bool validatePage(); - - void fitInView(); -protected: - void resizeEvent(QResizeEvent *event); - void showEvent(QShowEvent *event); - -private: - Ui::FixedWingPage *ui; - void setupFixedWingTypesCombo(); - QGraphicsSvgItem *m_fixedwingPic; - void updateAvailableTypes(); - QList m_descriptions; - -private slots: - void updateImageAndDescription(); +public: + bool validatePage(SelectionItem* seletedItem); + void setupSelection(Selection *selection); }; #endif // FIXEDWINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui deleted file mode 100644 index 59039632a..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.ui +++ /dev/null @@ -1,170 +0,0 @@ - - - FixedWingPage - - - - 0 - 0 - 600 - 400 - - - - WizardPage - - - - - - <!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:12pt; font-weight:600;">OpenPilot Fixed-wing 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 fixed-wing flying aircraft utilizing servos. The wizard supports the most common types of fixed-wing aircraft, other variants of fixed-wing aircraft 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 fixed-wing you want to create a configuration for below:</span></p></body></html> - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - - 4 - - - - - - - 4 - - - - - - 0 - 0 - - - - - 10 - 50 - false - - - - Fixed-wing type: - - - - - - - - 0 - 0 - - - - - 125 - 20 - - - - - - - - - - - 0 - 0 - - - - Qt::ScrollBarAlwaysOn - - - Qt::ScrollBarAlwaysOff - - - Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse - - - - - - - - - - 0 - 0 - - - - - 200 - 200 - - - - true - - - QFrame::NoFrame - - - 0 - - - 0 - - - Qt::ScrollBarAlwaysOff - - - Qt::ScrollBarAlwaysOff - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - false - - - - - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp index da3a73beb..ab3bb0576 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp @@ -26,165 +26,69 @@ */ #include "multipage.h" -#include "ui_multipage.h" #include "setupwizard.h" MultiPage::MultiPage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), - ui(new Ui::MultiPage) + SelectionPage(wizard, QString(":/configgadget/images/multirotor-shapes.svg"), parent) { - ui->setupUi(this); - - QSvgRenderer *renderer = new QSvgRenderer(); - renderer->load(QString(":/configgadget/images/multirotor-shapes.svg")); - m_multiPic = new QGraphicsSvgItem(); - m_multiPic->setSharedRenderer(renderer); - QGraphicsScene *scene = new QGraphicsScene(this); - scene->addItem(m_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())); - ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect()); - ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio); } MultiPage::~MultiPage() { - delete ui; } -void MultiPage::initializePage() +bool MultiPage::validatePage(SelectionItem *selectedItem) { - updateAvailableTypes(); - updateImageAndDescription(); -} - -bool MultiPage::validatePage() -{ - SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE)ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); - - getWizard()->setVehicleSubType(type); + getWizard()->setVehicleSubType((SetupWizard::VEHICLE_SUB_TYPE)selectedItem->id()); return true; } -void MultiPage::resizeEvent(QResizeEvent *event) +void MultiPage::setupSelection(Selection *selection) { - Q_UNUSED(event); - if (m_multiPic) { - ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect()); - ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio); - } -} - -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 X"), SetupWizard::MULTI_ROTOR_HEXA_X); - m_descriptions << tr("Hexacopter X"); - - ui->typeCombo->addItem(tr("Hexacopter H"), SetupWizard::MULTI_ROTOR_HEXA_H); - m_descriptions << tr("Hexacopter H"); - - ui->typeCombo->addItem(tr("Hexacopter Coax (Y6)"), SetupWizard::MULTI_ROTOR_HEXA_COAX_Y); - m_descriptions << tr("Hexacopter Coax (Y6)"); - - - // 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_HEXA_X: - elementId = "quad-hexa-X"; - 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; - } - m_multiPic->setElementId(elementId); - ui->typeGraphicsView->setSceneRect(m_multiPic->boundingRect()); - ui->typeGraphicsView->fitInView(m_multiPic, Qt::KeepAspectRatio); - - ui->typeDescription->setText(description); + selection->setTitle(tr("OpenPilot Multirotor Configuration")); + selection->setText(tr("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.\n\n" + "Please select the type of multirotor you want to create a configuration for below:")); + selection->addItem(tr("Tricopter"), + 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."), + "tri", + SetupWizard::MULTI_ROTOR_TRI_Y); + + selection->addItem(tr("Quadcopter X"), + 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."), + "quad-x", + SetupWizard::MULTI_ROTOR_QUAD_X); + + selection->addItem(tr("Quadcopter +"), + 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."), + "quad-plus", + SetupWizard::MULTI_ROTOR_QUAD_PLUS); + + selection->addItem(tr("Hexacopter"), + tr("A multirotor with six motors, one motor in front."), + "quad-hexa", + SetupWizard::MULTI_ROTOR_HEXA); + + selection->addItem(tr("Hexacopter X"), + tr("A multirotor with six motors, two motors in front."), + "quad-hexa-X", + SetupWizard::MULTI_ROTOR_HEXA_X); + + selection->addItem(tr("Hexacopter H"), + tr("A multirotor with six motors in two rows."), + "quad-hexa-H", + SetupWizard::MULTI_ROTOR_HEXA_H); + + selection->addItem(tr("Hexacopter Coax (Y6)"), + tr("A multirotor with six motors mounted in a coaxial fashion."), + "hexa-coax", + SetupWizard::MULTI_ROTOR_HEXA_COAX_Y); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h index ced899ebe..20cc10fd6 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h @@ -28,38 +28,18 @@ #ifndef MULTIPAGE_H #define MULTIPAGE_H -#include -#include -#include +#include "selectionpage.h" -#include "abstractwizardpage.h" - -namespace Ui { -class MultiPage; -} - -class MultiPage : public AbstractWizardPage { +class MultiPage : public SelectionPage { Q_OBJECT public: explicit MultiPage(SetupWizard *wizard, QWidget *parent = 0); - ~MultiPage(); + virtual ~MultiPage(); - void initializePage(); - bool validatePage(); - -protected: - void resizeEvent(QResizeEvent *event); - -private: - Ui::MultiPage *ui; - void setupMultiTypesCombo(); - QGraphicsSvgItem *m_multiPic; - void updateAvailableTypes(); - QList m_descriptions; - -private slots: - void updateImageAndDescription(); +public: + bool validatePage(SelectionItem *selectedItem); + void setupSelection(Selection *selection); }; #endif // MULTIPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui deleted file mode 100644 index 092c76187..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui +++ /dev/null @@ -1,164 +0,0 @@ - - - MultiPage - - - - 0 - 0 - 600 - 400 - - - - WizardPage - - - - - - <!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: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> - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - - 4 - - - - - - - 4 - - - - - - 125 - 36 - - - - - 10 - 50 - false - - - - Multirotor type: - - - - - - - - 125 - 20 - - - - - - - - - - - 0 - 0 - - - - Qt::ScrollBarAlwaysOn - - - Qt::ScrollBarAlwaysOff - - - Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse - - - - - - - - - - 0 - 0 - - - - - 200 - 200 - - - - true - - - QFrame::NoFrame - - - 0 - - - 0 - - - Qt::ScrollBarAlwaysOff - - - Qt::ScrollBarAlwaysOff - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - false - - - - - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp index a296d2521..6dea1edd5 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp @@ -30,7 +30,7 @@ #include "setupwizard.h" SelectionPage::SelectionPage(SetupWizard *wizard, QString shapeFile, QWidget *parent) : - AbstractWizardPage(wizard, parent), + AbstractWizardPage(wizard, parent), Selection(), ui(new Ui::SelectionPage) { ui->setupUi(this); @@ -108,12 +108,21 @@ void SelectionPage::addItem(QString name, QString description, QString shapeId, m_selectionItems << new SelectionItem(name, description, shapeId, id); } -void SelectionPage::setTitleLabel(QString text) +void SelectionPage::setTitle(QString title) { - ui->label->setText(text); + ui->label->setText(title); +} + +void SelectionPage::setText(QString text) +{ + ui->text->setText(text); } SelectionItem::SelectionItem(QString name, QString description, QString shapeId, int id) : m_name(name), m_description(description), m_shapeId(shapeId), m_id(id) { } + +SelectionItem::~SelectionItem() +{ +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h index a3b0d2dd7..3e39b565a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h @@ -38,8 +38,7 @@ namespace Ui { class SelectionPage; } -class SelectionItem : public QObject { - Q_OBJECT +class SelectionItem { public: SelectionItem(QString name, QString description, QString shapeId, int id); ~SelectionItem(); @@ -58,11 +57,13 @@ private: class Selection { public: + Selection() {} virtual void addItem(QString name, QString description, QString shapeId, int id) = 0; - virtual void setTitleLabel(QString text) = 0; + virtual void setTitle(QString title) = 0; + virtual void setText(QString text) = 0; }; -class SelectionPage : public AbstractWizardPage, Selection { +class SelectionPage : public AbstractWizardPage, public Selection { Q_OBJECT public: @@ -72,7 +73,8 @@ public: void initializePage(); bool validatePage(); void addItem(QString name, QString description, QString shapeId, int id); - void setTitleLabel(QString text); + void setTitle(QString title); + void setText(QString text); virtual void setupSelection(Selection *selection) = 0; virtual bool validatePage(SelectionItem *selectedItem) = 0; @@ -89,8 +91,6 @@ private: private slots: void selectionChanged(int index); void fitImage(); - - }; #endif // SUBVEHICLEPAGEPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.ui index b86e9d4ac..772009a49 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.ui @@ -16,11 +16,31 @@ + + + 13 + 75 + true + + placeholder_text + + Qt::PlainText + - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + Qt::AlignCenter + + + true + + + + + + + TextLabel true @@ -56,13 +76,6 @@ 0 - - - 10 - 50 - false - - Select: @@ -119,7 +132,7 @@ true - QFrame::StyledPanel + QFrame::NoFrame QFrame::Plain @@ -157,6 +170,9 @@ false + + QPainter::Antialiasing|QPainter::HighQualityAntialiasing + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index d41e58eae..cc307a868 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -78,8 +78,6 @@ FORMS += \ pages/controllerpage.ui \ pages/vehiclepage.ui \ pages/notyetimplementedpage.ui \ - pages/multipage.ui \ - pages/fixedwingpage.ui \ pages/helipage.ui \ pages/surfacepage.ui \ pages/inputpage.ui \ From b61471e8ef6298c3c7a9a85abc64a53a277478fa Mon Sep 17 00:00:00 2001 From: m_thread Date: Tue, 2 Sep 2014 13:49:01 +0200 Subject: [PATCH 105/203] OP-1222 Fixed a merge regression. --- .../src/plugins/setupwizard/pages/selectionpage.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp index 6dea1edd5..9a93c7cd4 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp @@ -122,7 +122,3 @@ SelectionItem::SelectionItem(QString name, QString description, QString shapeId, m_name(name), m_description(description), m_shapeId(shapeId), m_id(id) { } - -SelectionItem::~SelectionItem() -{ -} From 655d02622f8863f21533fe107e171aa6327c82e4 Mon Sep 17 00:00:00 2001 From: m_thread Date: Tue, 2 Sep 2014 14:01:02 +0200 Subject: [PATCH 106/203] OP-1222 Minor ordering adjustments. --- ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp | 1 + .../src/plugins/setupwizard/pages/selectionpage.cpp | 2 +- 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp index ab3bb0576..cd987f494 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp @@ -50,6 +50,7 @@ void MultiPage::setupSelection(Selection *selection) "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.\n\n" "Please select the type of multirotor you want to create a configuration for below:")); + selection->addItem(tr("Tricopter"), 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 " diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp index 9a93c7cd4..309f7bd38 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp @@ -65,7 +65,7 @@ void SelectionPage::initializePage() // Default to first item if any if (ui->typeCombo->count() > 0) { - ui->typeCombo->setCurrentIndex(1); + ui->typeCombo->setCurrentIndex(0); } } } From 4bf932d36b80e2da26b06ca6c7bb155511dc3bb3 Mon Sep 17 00:00:00 2001 From: m_thread Date: Tue, 2 Sep 2014 16:46:40 +0200 Subject: [PATCH 107/203] OP-1222 Uncrustification. --- .../setupwizard/pages/fixedwingpage.cpp | 14 ++++---- .../plugins/setupwizard/pages/fixedwingpage.h | 2 +- .../plugins/setupwizard/pages/multipage.cpp | 32 +++++++++---------- .../setupwizard/pages/selectionpage.cpp | 8 ++--- .../plugins/setupwizard/pages/selectionpage.h | 28 +++++++++++----- 5 files changed, 46 insertions(+), 38 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index 1a2006c22..41e7144a8 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -30,12 +30,10 @@ FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) : SelectionPage(wizard, QString(":/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg"), parent) -{ -} +{} FixedWingPage::~FixedWingPage() -{ -} +{} bool FixedWingPage::validatePage(SelectionItem *seletedItem) { @@ -53,19 +51,19 @@ void FixedWingPage::setupSelection(Selection *selection) "Please select the type of fixed-wing you want to create a configuration for below:")); selection->addItem(tr("Aileron Dual Servos"), tr("This setup expects a traditional airframe using two independent aileron servos " - "on their own channel (not connected by Y adapter) plus an elevator and a rudder."), + "on their own channel (not connected by Y adapter) plus an elevator and a rudder."), "aileron", SetupWizard::FIXED_WING_DUAL_AILERON); selection->addItem(tr("Aileron Single Servo"), tr("This setup expects a traditional airframe using a single alieron servo or two servos " - "connected by a Y adapter plus an elevator and a rudder."), + "connected by a Y adapter plus an elevator and a rudder."), "aileron-single", - SetupWizard::FIXED_WING_AILERON); + SetupWizard::FIXED_WING_AILERON); selection->addItem(tr("Elevon"), tr("This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet " - "supported. Setup should include only two elevons, and should explicitly not include a rudder."), + "supported. Setup should include only two elevons, and should explicitly not include a rudder."), "elevon", SetupWizard::FIXED_WING_ELEVON); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h index 8bd02f0e5..82c8f21b6 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h @@ -38,7 +38,7 @@ public: ~FixedWingPage(); public: - bool validatePage(SelectionItem* seletedItem); + bool validatePage(SelectionItem *seletedItem); void setupSelection(Selection *selection); }; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp index cd987f494..96ab087f6 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp @@ -30,12 +30,10 @@ MultiPage::MultiPage(SetupWizard *wizard, QWidget *parent) : SelectionPage(wizard, QString(":/configgadget/images/multirotor-shapes.svg"), parent) -{ -} +{} MultiPage::~MultiPage() -{ -} +{} bool MultiPage::validatePage(SelectionItem *selectedItem) { @@ -47,31 +45,31 @@ void MultiPage::setupSelection(Selection *selection) { selection->setTitle(tr("OpenPilot Multirotor Configuration")); selection->setText(tr("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.\n\n" - "Please select the type of multirotor you want to create a configuration for below:")); + "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.\n\n" + "Please select the type of multirotor you want to create a configuration for below:")); selection->addItem(tr("Tricopter"), 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."), + "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."), "tri", SetupWizard::MULTI_ROTOR_TRI_Y); selection->addItem(tr("Quadcopter X"), 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."), + "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."), "quad-x", SetupWizard::MULTI_ROTOR_QUAD_X); selection->addItem(tr("Quadcopter +"), - 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."), - "quad-plus", - SetupWizard::MULTI_ROTOR_QUAD_PLUS); + 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."), + "quad-plus", + SetupWizard::MULTI_ROTOR_QUAD_PLUS); selection->addItem(tr("Hexacopter"), tr("A multirotor with six motors, one motor in front."), diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp index 309f7bd38..a00275244 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp @@ -56,10 +56,10 @@ SelectionPage::~SelectionPage() void SelectionPage::initializePage() { - //lazy init + // lazy init if (m_selectionItems.isEmpty()) { setupSelection(this); - foreach (SelectionItem * item, m_selectionItems) { + foreach(SelectionItem * item, m_selectionItems) { ui->typeCombo->addItem(item->name()); } @@ -98,6 +98,7 @@ void SelectionPage::showEvent(QShowEvent *event) void SelectionPage::selectionChanged(int index) { SelectionItem *item = m_selectionItems.at(index); + m_shape->setElementId(item->shapeId()); ui->typeDescription->setText(item->description()); fitImage(); @@ -120,5 +121,4 @@ void SelectionPage::setText(QString text) SelectionItem::SelectionItem(QString name, QString description, QString shapeId, int id) : m_name(name), m_description(description), m_shapeId(shapeId), m_id(id) -{ -} +{} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h index 95ff03ecd..039a639f9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h @@ -41,12 +41,24 @@ class SelectionPage; class SelectionItem { public: SelectionItem(QString name, QString description, QString shapeId, int id); -// ~SelectionItem(); +// ~SelectionItem(); - QString name() { return m_name; } - QString description() { return m_description; } - QString shapeId() { return m_shapeId; } - int id() { return m_id; } + QString name() + { + return m_name; + } + QString description() + { + return m_description; + } + QString shapeId() + { + return m_shapeId; + } + int id() + { + return m_id; + } private: QString m_name; @@ -60,7 +72,7 @@ public: Selection() {} virtual void addItem(QString name, QString description, QString shapeId, int id) = 0; virtual void setTitle(QString title) = 0; - virtual void setText(QString text) = 0; + virtual void setText(QString text) = 0; }; class SelectionPage : public AbstractWizardPage, public Selection { @@ -81,12 +93,12 @@ public: protected: void resizeEvent(QResizeEvent *event); - void showEvent(QShowEvent * event); + void showEvent(QShowEvent *event); private: Ui::SelectionPage *ui; QGraphicsSvgItem *m_shape; - QList m_selectionItems; + QList m_selectionItems; private slots: void selectionChanged(int index); From 82a32a5d8e88c726a269cfe35db804441bdf338f Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Wed, 3 Sep 2014 02:19:15 +1000 Subject: [PATCH 108/203] Create airspeed page --- .../setupwizard/pages/airspeedpage.cpp | 123 ++++--------- .../plugins/setupwizard/pages/airspeedpage.h | 32 +--- .../plugins/setupwizard/pages/airspeedpage.ui | 164 ------------------ .../src/plugins/setupwizard/setupwizard.cpp | 7 +- .../src/plugins/setupwizard/setupwizard.h | 14 +- .../src/plugins/setupwizard/setupwizard.pro | 2 + .../setupwizard/vehicleconfigurationsource.h | 6 +- 7 files changed, 57 insertions(+), 291 deletions(-) delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.ui diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index 3c7834e2d..4bc0db2b8 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -26,109 +26,44 @@ */ #include "airspeedpage.h" -#include "ui_airspeed.h" #include "setupwizard.h" AirSpeedPage::AirSpeedPage(SetupWizard *wizard, QWidget *parent) : - AbstractWizardPage(wizard, parent), - ui(new Ui::AirSpeedPage) -{ - ui->setupUi(this); - QSvgRenderer *renderer = new QSvgRenderer(); - renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); - m_airspeedPic = new QGraphicsSvgItem(); - m_airspeedPic->setSharedRenderer(renderer); - QGraphicsScene *scene = new QGraphicsScene(this); - scene->addItem(m_airspeedPic); - ui->typeGraphicsView->setScene(scene); - - setupAirSpeedPageTypesCombo(); - - // Default to Software Estimation - connect(ui->typeCombo, SIGNAL(currentIndexChanged(int)), this, SLOT(updateImageAndDescription())); - ui->typeCombo->setCurrentIndex(0); -} + SelectionPage(wizard, QString(":/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg"), parent) +{} AirSpeedPage::~AirSpeedPage() -{ - delete ui; -} +{} -void AirSpeedPage::initializePage() +bool AirSpeedPage::validatePage(SelectionItem *seletedItem) { - updateAvailableTypes(); - updateImageAndDescription(); -} - -// TODO -bool AirSpeedPage::validatePage() -{ - SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE)ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); - - getWizard()->setVehicleSubType(type); + getWizard()->setAirspeedType((SetupWizard::AIRSPEED_TYPE)seletedItem->id()); return true; } -void AirSpeedPage::fitInView() +void AirSpeedPage::setupSelection(Selection *selection) { - if (m_airspeedPic) { - ui->typeGraphicsView->setSceneRect(m_airspeedPic->boundingRect()); - ui->typeGraphicsView->fitInView(m_airspeedPic, Qt::KeepAspectRatio); - } -} - -void AirSpeedPage::resizeEvent(QResizeEvent *event) -{ - Q_UNUSED(event); - fitInView(); -} - -void AirSpeedPage::showEvent(QShowEvent *event) -{ - Q_UNUSED(event); - fitInView(); -} - -// TODO -void AirSpeedPage::setupAirSpeedPageTypesCombo() -{ - ui->typeCombo->addItem(tr("Aileron Dual Servos"), SetupWizard::FIXED_WING_DUAL_AILERON); - m_descriptions << tr("This setup expects a traditional airframe using two independent aileron servos on their own channel (not connected by Y adapter) plus an elevator and a rudder. "); - - ui->typeCombo->addItem(tr("Aileron Single Servo"), SetupWizard::FIXED_WING_AILERON); - m_descriptions << tr("This setup expects a traditional airframe using a single alieron servo or two servos connected by a Y adapter plus an elevator and a rudder. "); - - ui->typeCombo->addItem(tr("Elevon"), SetupWizard::FIXED_WING_ELEVON); - m_descriptions << tr("This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet supported. Setup should include only two elevons, and should explicitly not include a rudder."); -} - -void AirSpeedPage::updateAvailableTypes() -{} - -// TODO -void AirSpeedPage::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::FIXED_WING_DUAL_AILERON: - elementId = "aileron"; - break; - case SetupWizard::FIXED_WING_AILERON: - elementId = "aileron-single"; - break; - case SetupWizard::FIXED_WING_ELEVON: - elementId = "elevon"; - break; - default: - elementId = ""; - break; - } - m_airspeedPic->setElementId(elementId); - ui->typeGraphicsView->setSceneRect(m_airspeedPic->boundingRect()); - ui->typeGraphicsView->fitInView(m_airspeedPic, Qt::KeepAspectRatio); - - ui->typeDescription->setText(description); + selection->setTitle(tr("OpenPilot Airspeed Sensor Selection")); + selection->setText(tr("This part of the wizard will help you select and configure " + "flying aircraft utilizing servos. The wizard supports the most common types of fixed-wing " + "aircraft, other variants of fixed-wing aircraft can be configured by using custom " + "configuration options in the Configuration plugin in the GCS.\n\n" + "Please select the type of fixed-wing you want to create a configuration for below:")); + selection->addItem(tr("Estimated"), + tr("This setup expects a traditional airframe using two independent aileron servos " + "on their own channel (not connected by Y adapter) plus an elevator and a rudder."), + "aileron", + SetupWizard::ESTIMATE); + + selection->addItem(tr("EagleTree"), + tr("This setup expects a traditional airframe using a single alieron servo or two servos " + "connected by a Y adapter plus an elevator and a rudder."), + "aileron-single", + SetupWizard::EAGLETREE); + + selection->addItem(tr("MS4525 Based"), + tr("This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet " + "supported. Setup should include only two elevons, and should explicitly not include a rudder."), + "elevon", + SetupWizard::MS4525); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h index 0e3940c67..9b72c967b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h @@ -28,40 +28,18 @@ #ifndef AIRSPEEDPAGE_H #define AIRSPEEDPAGE_H -#include -#include -#include +#include "selectionpage.h" -#include "abstractwizardpage.h" - -namespace Ui { -class AirSpeedPage; -} - -class AirSpeedPage : public AbstractWizardPage { +class AirSpeedPage : public SelectionPage { Q_OBJECT public: explicit AirSpeedPage(SetupWizard *wizard, QWidget *parent = 0); ~AirSpeedPage(); - void initializePage(); - bool validatePage(); - - void fitInView(); -protected: - void resizeEvent(QResizeEvent *event); - void showEvent(QShowEvent *event); - -private: - Ui::AirSpeedPage *ui; - void setupAirSpeedPageTypesCombo(); - QGraphicsSvgItem *m_fixedwingPic; - void updateAvailableTypes(); - QList m_descriptions; - -private slots: - void updateImageAndDescription(); +public: + bool validatePage(SelectionItem *seletedItem); + void setupSelection(Selection *selection); }; #endif // AIRSPEEDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.ui deleted file mode 100644 index 824124bf3..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.ui +++ /dev/null @@ -1,164 +0,0 @@ - - - FixedWingPage - - - - 0 - 0 - 600 - 400 - - - - WizardPage - - - - - - <!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:12pt; font-weight:600;">OpenPilot Airspeed Sensor 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 an airspeed sensor also commonly called a Pitot tube. The OpenPilot Platform supports multiple types of hardware airspeed sensors as well as an advanced software based wind speed estimation algorthym which requires no additional hardware although this is slightly less accurate than using a dedicated hardware sensor. </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 airspeed sensor you wish to use below:</span></p></body></html> - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - - 4 - - - - - - - 4 - - - - - - 125 - 36 - - - - - 10 - 50 - false - - - - Airspeed type: - - - - - - - - 125 - 20 - - - - - - - - - - - 0 - 0 - - - - Qt::ScrollBarAlwaysOn - - - Qt::ScrollBarAlwaysOff - - - Qt::TextSelectableByKeyboard|Qt::TextSelectableByMouse - - - - - - - - - - 0 - 0 - - - - - 200 - 200 - - - - true - - - QFrame::NoFrame - - - 0 - - - 0 - - - Qt::ScrollBarAlwaysOff - - - Qt::ScrollBarAlwaysOff - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - false - - - - - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 4598f02f9..408f923fe 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -32,6 +32,7 @@ #include "pages/vehiclepage.h" #include "pages/multipage.h" #include "pages/fixedwingpage.h" +#include "pages/airspeedpage.h" #include "pages/helipage.h" #include "pages/surfacepage.h" #include "pages/inputpage.h" @@ -147,7 +148,7 @@ int SetupWizard::nextId() const { switch (getVehicleType()) { case VEHICLE_FIXEDWING: - return PAGE_AIRFRAMESTAB_FIXEDWING; + return PAGE_AIRSPEED; // TODO: Pages for Multi and heli case VEHICLE_MULTI: @@ -158,6 +159,9 @@ int SetupWizard::nextId() const } } + case PAGE_AIRSPEED: + return PAGE_AIRFRAMESTAB_FIXEDWING; + case PAGE_AIRFRAMESTAB_FIXEDWING: return PAGE_SAVE; @@ -355,6 +359,7 @@ void SetupWizard::createPages() setPage(PAGE_VEHICLES, new VehiclePage(this)); setPage(PAGE_MULTI, new MultiPage(this)); setPage(PAGE_FIXEDWING, new FixedWingPage(this)); + setPage(PAGE_AIRSPEED, new AirSpeedPage(this)); setPage(PAGE_HELI, new HeliPage(this)); setPage(PAGE_SURFACE, new SurfacePage(this)); setPage(PAGE_INPUT, new InputPage(this)); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h index b19323559..3ef48ee5f 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -96,6 +96,16 @@ public: return m_servoType; } + void setAirspeedType(SetupWizard::AIRSPEED_TYPE setting) + { + m_airspeedType = setting; + } + SetupWizard::AIRSPEED_TYPE getAirspeedType() const + { + return m_airspeedType; + } + + void setGPSSetting(SetupWizard::GPS_SETTING setting) { m_gpsSetting = setting; @@ -165,7 +175,7 @@ private slots: void pageChanged(int currId); private: enum { PAGE_START, PAGE_CONTROLLER, PAGE_VEHICLES, PAGE_MULTI, PAGE_FIXEDWING, - PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_ESC, PAGE_SERVO, + PAGE_AIRSPEED, PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_ESC, PAGE_SERVO, PAGE_BIAS_CALIBRATION, PAGE_REVO_CALIBRATION, PAGE_OUTPUT_CALIBRATION, PAGE_SAVE, PAGE_SUMMARY, PAGE_NOTYETIMPLEMENTED, PAGE_AIRFRAMESTAB_FIXEDWING, PAGE_REBOOT, PAGE_END, PAGE_UPDATE }; @@ -179,7 +189,7 @@ private: INPUT_TYPE m_inputType; ESC_TYPE m_escType; SERVO_TYPE m_servoType; - + AIRSPEED_TYPE m_airspeedType; GPS_SETTING m_gpsSetting; RADIO_SETTING m_radioSetting; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index cc307a868..ae895118a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -19,6 +19,7 @@ HEADERS += setupwizardplugin.h \ pages/notyetimplementedpage.h \ pages/multipage.h \ pages/fixedwingpage.h \ + pages/airspeedpage.h \ pages/helipage.h \ pages/surfacepage.h \ pages/abstractwizardpage.h \ @@ -49,6 +50,7 @@ SOURCES += setupwizardplugin.cpp \ pages/notyetimplementedpage.cpp \ pages/multipage.cpp \ pages/fixedwingpage.cpp \ + pages/airspeedpage.cpp \ pages/helipage.cpp \ pages/surfacepage.cpp \ pages/abstractwizardpage.cpp \ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index f666a1d35..c42fbe6a8 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -64,8 +64,8 @@ public: enum ESC_TYPE { ESC_RAPID, ESC_STANDARD, ESC_UNKNOWN }; enum SERVO_TYPE { SERVO_ANALOG, SERVO_DIGITAL, SERVO_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN }; - - enum GPS_SETTING { GPS_UBX, GPS_NMEA, GPS_DISABLED }; + enum AIRSPEED_TYPE { ESTIMATE, EAGLETREE, MS4525 }; + enum GPS_SETTING { GPS_PLAT, GPS_UBX, GPS_NMEA, GPS_DISABLED }; enum RADIO_SETTING { RADIO_TELEMETRY, RADIO_DISABLED }; virtual VehicleConfigurationSource::CONTROLLER_TYPE getControllerType() const = 0; @@ -74,7 +74,7 @@ public: virtual VehicleConfigurationSource::INPUT_TYPE getInputType() const = 0; virtual VehicleConfigurationSource::ESC_TYPE getEscType() const = 0; virtual VehicleConfigurationSource::SERVO_TYPE getServoType() const = 0; - + virtual VehicleConfigurationSource::AIRSPEED_TYPE getAirspeedType() const = 0; virtual VehicleConfigurationSource::GPS_SETTING getGPSSetting() const = 0; virtual VehicleConfigurationSource::RADIO_SETTING getRadioSetting() const = 0; From b9f89e39e724abacd6076385444f7396c4a9fbba Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Wed, 3 Sep 2014 02:22:09 +1000 Subject: [PATCH 109/203] Uncrustify --- ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h | 2 +- .../src/plugins/setupwizard/vehicleconfigurationsource.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h index 3ef48ee5f..ef4561567 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -102,7 +102,7 @@ public: } SetupWizard::AIRSPEED_TYPE getAirspeedType() const { - return m_airspeedType; + return m_airspeedType; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index c42fbe6a8..90f70114f 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -74,7 +74,7 @@ public: virtual VehicleConfigurationSource::INPUT_TYPE getInputType() const = 0; virtual VehicleConfigurationSource::ESC_TYPE getEscType() const = 0; virtual VehicleConfigurationSource::SERVO_TYPE getServoType() const = 0; - virtual VehicleConfigurationSource::AIRSPEED_TYPE getAirspeedType() const = 0; + virtual VehicleConfigurationSource::AIRSPEED_TYPE getAirspeedType() const = 0; virtual VehicleConfigurationSource::GPS_SETTING getGPSSetting() const = 0; virtual VehicleConfigurationSource::RADIO_SETTING getRadioSetting() const = 0; From acee61b3b18fc5737bb5148cebafb2b2ec8cd462 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Wed, 3 Sep 2014 02:39:18 +1000 Subject: [PATCH 110/203] Skip bias calib on fixed wings --- .../openpilotgcs/src/plugins/setupwizard/setupwizard.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 408f923fe..cfe121966 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -171,8 +171,12 @@ int SetupWizard::nextId() const case CONTROLLER_CC: case CONTROLLER_CC3D: case CONTROLLER_REVO: - return PAGE_BIAS_CALIBRATION; - + switch (getVehicleType()) { + case VEHICLE_FIXEDWING: + return PAGE_OUTPUT_CALIBRATION; + default: + return PAGE_BIAS_CALIBRATION; + } default: return PAGE_NOTYETIMPLEMENTED; } From bc70db575d2fd9f42fc5efb7607c27d095370eb8 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Tue, 2 Sep 2014 20:22:07 +0200 Subject: [PATCH 111/203] OP-1222 FW_Wizard New artwork for connection diagram button (up/down or hover), added to wizardResources.qrc --- .../resources/bttn-illustration-color-down.png | Bin 0 -> 19061 bytes .../resources/bttn-illustration-color-up.png | Bin 0 -> 19272 bytes .../src/plugins/setupwizard/wizardResources.qrc | 2 ++ 3 files changed, 2 insertions(+) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-color-down.png create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-color-up.png diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-color-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-color-down.png new file mode 100644 index 0000000000000000000000000000000000000000..0ff71883157daf6894c4f3008ec61d95c93c0a30 GIT binary patch literal 19061 zcma(2byOSe7x;_PLR;J^?(XhZthjrDLV(~-uwsQG#fv+%NN{&AUNi-YySoH;&b;5> zIcuGJ?>{$dO=L2Yd1gP)w$I*)&`^`dKqWy%KtRAyRFKsIUQ2zz)oU_oB>4J*$UzXaswlHd3kZzI@!Bh zfLy>F&TiJ3Ct@VPL3sZiB;^6Iadtxhj&uJ4^0Eav*@MtKl~WNAUNQgowJg}(!p+tN zV(aXLK=aYo$&%d-?BW2j0Mk&}S~xpVS-CkoQi(}X*|>qN#A$3G5El_nP6)`!+L^=3 z4GgvfyW2yYUH-c$r_O(SO@SZ$Z;z>lo3kC*0zxA}^}qd8|MzDqF-|E7Dhy*MF=;J{ z|2E*Qwyl!|n939E<_?U4ii<;tLzwIT>#YCA;!XwJE0uO%Jg9fA{Q8s{?j(bT@UjGSzhlbMSur{~7N`Db4?lIb@~7 z6_6?Qe?pUS1B3oMn@Y#l5sbjY#m&Xe#mmkuq{G84!XqTY%dfqtg9#k0{eNc3!_5MW z@So`10oggbfSoKHY+XQZkpD@|5)1*^I&kvx@Nx70AHlMNEo~v}R{yWLU^n++|9?*) zSsua+@bilQ8;i4xkDINv4Fuu;Lo!tV_f%Q@Z>XMN3ui}1;CBCaNkD#JCwH(rr_29j zY56}3C-yW&8M%$*13RO^X*~DGIEH=qWM}Kgl~7%jd*pZr*)^hd`feQa!PTvlz4)$Uw)v1LU&VG6AR^Krj1SM~BmVCL zg}J`IH_IKfTHLK(l&`I;1MBM(+Rv27UtL|fjb-p3&DF@L4fR4$La-H>@5&aPt6oze zalCWeZKkn?ry`=%2j6BaZu|W?h3`>xt-1)24XmyGd>m2_pvlit4o#AcQJUz*z_?Lh z?iw`=&gow=FB-FIn>~cr+h#zC!$3Ov`lMe~7)=ttvxKZ&i=O-uMBkMEje+M}y?Csn zr>CKz!DX5(6eWm46OT+zPJVfHRTN2qCw*s=BKk7eD)HX6#hB!0YHDf`o&9Ug3i#f7 zuO!k*bQo)7Ps8lzvAbR8y!v`1InA9SD{DA3Wc74+Z^Gj7K)-8euIBodNmch)P^3=W z*RhqtO^7UhW#zL!aLWU-wVz~TX!lirSLLA$kBl_$=Cm2q7N8>Zav>v0BL!0jcVoAL zvLah^`ib9$FUKw(_Z_=!KtvD{MY~>}ro`^HPXF?;XVeRi9Cu0~bJG=~TY|x%{Hjw7 zN_s|qJE~)2Z+8K+ZsET;_&xh45SOuJGw&IS-!0h35moah8R@KgS4%+l8rG=9>gtVFI%@I z!(2~~j3c7LixF_QNwE-Y@AmoP(u`W;^q79Y7BM zCM!+N#~z%7OC7>*l6m5M`FsnTIE4qkOiC8nC(du7{m4#K4hVSlCNxw>m$TQYiI*Hb zE?VnHu8gj3vYd|XpX9Il$d9F!5A-3mwYBw)jdq9>sf~bseh1W(8oxgQN)Z>Hmq!yO zKfsd{m5oWWj{VfJY!mPD8f7y=h*)v6YtV>YYd%D~zbNxny3?(+Ji}GG({e#lG&&Zy z7~h`>T6VHZ$v;qbLXA&)Ij$5I76Aw&2}ouNhA}^!A~tYwi;^%iS5NgLqYnFH$wfmj zes99Rf8a_ZV6UD%Y(V9o6@NZkL&%pwOu0m2Vr9)QCRvtn;Jh(+fB4N9Am1bNDdV22-4Gq0JK8sOcwY0RbeX3^yTa0@U20}53d4g;$ zUW8!cH)L@V_e`yoQ?paOzrHzF?_{}KClr1_&g3gFi7#d<4g-CE^vfk8Ls|sPtgOF( zhlY;F3SDXC;pL5|(dyyBLGxCEGVWyB^7q^iR3GSY(|KSnLMqnQjDQV;czO=NASx)S zBXT}I!cl~r(DHJ&^+6syb5&-k_f$|LbzNOxN}7#1$S~cZipbs9$BV8)WPUFXtMAs< zg8X%Kbbh2tBAQ|&%4uqFh1e0b=9QKbk&)s5X8@QrqoShrDTx%^Z;niRJ~#_zK&eB1 zZ@alp$PpU4YAM~{-|wBCsuQgh^{%Z^sj8|17PZj9L01?4r6UDtnlGlNhI?RO;Ot>c z%8!d^>rXr_nXns@t}Zh>JGeiRU}nybX6M^?Ynm2+2}(1T#W!!>%wRnRqj9YD6Pgy( z)Zp}TdGEtGU6x~<)4TBsXbSU?QrAm7qbnvgaBQ(sET zr#<-ySsL`q8*UykX*DO2)4%^5EgQ3`u_HBfb@y7yRe4)LB{sH-BH5nm@p3|BJzVG^ z*ns8M{7k`XfsT%DK&PsI2F#+24C3+eF$&nY#f_d+z`+c@(NCNxqlu4-ips>qwDx!b zW5h=OJ2}~NvfM^YMpjT!5wkfMr)^|3a=tyH{Uu_I5Qk8toAF#`)&p4UOdK2^k%MLr z!B6*BN6T%5UxR`=6~AYk5Px?)wFMEq4f_?f$C@^o!o{8gRUpHBQvoY1EOZU!X?rZ# z?eD0bn9#gFnz!(nM@UXiHg@eNz$YYBH_X|?q9aFHauVFla>oRmIq2p2sr_)fb%#U3ZzI(PDvkd0i~nR~ag4d3p-We)eUbo}N~;Elfg>yY&uu;m!~Z+at&1 z;UY12;fr2oU>bGROxi3EnjK4-F3i$4vf}4ROYqzrh$%N|OCdD%i|_Eg;o;)??G6(k zoT)Gx8W~YGS=Ii~r>%OukNG0~>&JA8atd2b&%67F$#Yi*{tWFrXfQOBq&SJkIx`RPfu^4qG=_AZrSgds>`o4XxH@A@?}D*Cms^ZTf==W)8%ZXnG?m% zirV5dqSaVlQQPVr-rEgMHTh_0NZj?Xe2V<`+tETpR1B%0mZm266hpNOgTmZ?3ipaM z-s*^|KtU$TPIj?Exnc3GA)3i7UVrF0jTDlYge&alw8d+no*&3~XH4q$9VfqMTHV z_Mb46l$4qeE8D!c;^m1bD6CFbIviFz#Vb(kTZN|kat?R14tBjmhX_zZ?RfY4Gc&u55Vln<67NZiqT@EKPcZS`Ti8)^+EBC>eO6^ZxjCtGY7{G z5GOTlVDzpjO9sTh_*b&8cWykgH98yjG`bUNYaU7I;!m+-{0Ngx#SK^OK5VRW0uz+k z4--?MVQVg-zadz$*$10y6Rv-s_iylwg`aRfN5Hy#c?q+OFg}1l)PgJC`TXc}b=Fvf zCXk8t1XpSte}M#E6aM!FJp2=>+!PaplM4&Ob8|#yEPR1i`hm$@D|ZWK`XHm}HfeqX+`7ru7*|ImF?Q)B(4nIEQT`wwo2H9J?m^Rpwwh3eU{oQe=nH51L4k z*i7c_f<#TfSfr_vWOMaXO~ATf3I6RC;|4JEVd@}0eW1dw#p*NflZ=Jl+|F1gJFhMf z3w&HUShVTfuWb3P14}#R*H7b|92eEh?^n|g0_?Z4`{>As#rANr-comp8in^I!oY0@ zX4^3PqW<}{vYlblt^jE|5wR{cwi21}W)5%8Pga-luxcsFI!qo0}A^*GthaY_e_sB}^HXUMHOzz2n&pr&K>vm^1EHEh6> z-MGg54PaemX>dOK9ycU?{)~3~2F9ocHi6QWrfo|y5a&|}yY-=(*4yB0Z*Ql$x4%{I zSnB(Ajl+68(*Sl@)sO`@Y#0Ws3AU!bsXdEBaaoR1$rq9A=Eddnac z5kH;v^*3swLP5yi<}E#fZn@n7t6zXgdc1KqZR*t5)m?{(poI7G@$;*$K+tacVfg9) zq?BwihIUFgSk=kni##`4QU2m(CpuaMOS=fXTQ`kd7ruZvR|2R zli`$H1%-ww&`I0dv#z^%k1Kk&7VbztQfJq4AIKWnJsW(XRS)nlS<}IN)$>DMZSIeHgmJFVXpkC!?hs1yT*l$Ls?5ND-OHosBv(} zJf8o{{@YgSiV>pR^hg_$ZVe(;!S6OA8I?wfueFo_d;3A?>Py+}$;)=H_)J~ih)K^n z*I+DpCOk@V87VVvH@C)9M}fl+a;%EakvgJPupnZQ5s)(VF;;oQRoFZvnzq=!;#-aeroVE6}PR|7DK-E?NdST#)iY;Ma1*hD~s3F^A3Qj+&^eLX`y9hM0}kJ zQaR)bjTL8C5f2rS#~@Lk*@Kj%cl>s0GD6xTjbJvIH}ov{=PKf`xiuBfWQ7<3XEEC5 zeIbdqzrv--h}FqTg3Oh2=iEcrw?JXj@>fX6_JPrN??r`>YtziHPTwqOsj)z@~9kQQc zd&fX~*>@~s9W^z1HEL@`KkW;yl^pKMO|pFha0mHCGv!$RDlI&8Kq z#9pZhJJ#-v?02viz3&d<-SRDMpe zn-o1fPVuw-`EZ!KjHu=D1V4=BQw0L+EVU_1oeWA^xXlOJa>dqGUzAW9q3rwHk0d;r zhlG(OvN3piv5C4-X}BJ9giv3m4+fbl*C*nL+~6{*#aQeeyKn33pu=|zAyi%oG4Is` zadt@(rx{5EDJ{o88s^bszWiaG(>3HLizgkOqSYO1o_Y^V!`#`~G+%Z_W|X(zW`sl;83zwA zb|RC|LYL}Rumnu_tu#7>mzn9w89bi=k^^MwBL)FSbKLgJ?Ssc=GO7~3BxB9vIB#TT z_xBE{&C}3M#0)vIFd0k7!f5adu=j9jzJzGZnavTJ_fhU#K|S5htvnm6C5e6sI`ORa zOh>UvH#RgFa?-aJszMEz=thz1m=BpvmIMhEnygAoONVLfAa%8S2jh;rNrtk=6xu`j z%eQ_Ow}`^GGC22dw}w)^r?l&VPjDL$<$XsWUn3@(xT z=l^hR=z2I)q1;Nilk%e|a;a|FjdvyKojZ$$dc}>7SZS&GLlYJj7B7&VmzEZn4ioIM zcOUYgFuV%XBOi=yFw#!b)E8%_$5EB1d~p(%S5{P4=hPZj9E{sv!}{pmA>5dISh$bBtlA0M&58+Rr}Ko(KnqY&wi;_Q$GNpTAlAyVsvm?Qq8!GD8K%7iLieEXXEbr4m{ z-J7J8lmx}L{#57FUx_=Guhyzr+jsA$Q~1Q)wvgAWZ882MD?mOkT*r4ePH&ZY>M*9| zt{bbu9Z0I7^1Ck#M_R+k$X>As3S|&*T#yau6o$56985nxhUQ=B1`!vde(Sx?$8#xr@kR9s63D=(ZCnOKc=*e8MSgSgVxg)Xi1^B#!L)V5<3VWFx zFWvpER#M2l%6YKJ!^ims&K*XhAIEFUvsDcR`#^5OE^kYXL`0j5-&$KmSj$UFB64yl?91;P9a)?2HtblREd#$YUSHDSGpdE- zr6M&Y2@Nh679eHX#rd4Zg@buI4~|GTZ#Wy$>I}XvL(f8QJ}Y>pAcFngrJM%bwCUYP zakMglNXH6NGW!kOp#gdB{$uzv?{5-~r}~*Spp#Y7{OGjZQvF=$IbRN#fsEJZ;A@`C zstKX%XOmya(2B)D3s|n1kd0X}OITiPoc7>gDUC=G3@JSM(#Ga+Q?Mt9XYFVS>1H=$+EH ze5rsJb2M1TLYRa^I49EMa!i@eA^k`Nr82-hOrH+)D;_G_&y@g<$NR{w%$#8Modg#~t=K%KiH@SY6|IuMu8waKn3TtxE=C(eENX4T zMW-vH9!3^MU*e*p&mz?Qdd@S3$H#Y|nNCWEv-9njQxU{5lIq-0J!sz%ese@u_4v42 zz}<-HCsEw8QY8};aA@Hp>pGTs`Gjn!!GyCC;cjXIqy)4)u9c6HF-?kOi=aiGvw& z3M_ze(-5KO*^*>H*Dvn&_V<6))+S6&Y5|e;pYicVzEfZ4l|THMsqnSUsGg0PF#t2pN_i>Af-2K!W9cyRD*y>f%@KMD@qxd2kUzUJZK>G}H?yR=lx z*jUBOOYlGJcBjrCb#c2O`FSWPg`)GK@71-yHEuf8TF13As!UM#yvcd~LnWi@&`<;( zWAka}!`?~kn3{>lw65`&{X*LdBc@4@%J|BxePl7y-fuoPISG?X7yp1zEt!dvv#7L` zC8)sP-=9qU%Rdq{j!*U9frK+MDoXgvB@<`IB`yGP)z6-c_1nHz1>Uj%L8r;P*o#qC z$9f1lFTj2Huxmzj1ayC#dT3;&_WO)PwOC#7%&@VW(*WW2!_Db#&^rnRAvREN7{-$8 zAo&n`BK7=uLBv;;2m!;E@n&Y7-oGf}(kXQj*ue(}c9D^hL;&eixA?oTkWqa!w+a7| znrfXLLxLJ=w5b33NctsDAqJ zeA5L3m>eF-JwOU}$xpq*ugrP)#lexG42DH4>QFi{i}oU#c&;&waPDaM*x*1iL(`%o zxy$&i!@9M(0@lq zNBsBiwY0T+hm%>E+1UDyJ@ZRh1Txu6USafpnBoJ(O-oDLe!XB1u*FmWVbHEye&8av zI_bFiY-cx_B{sOEJd<9K%Q~8jAEPdrZW}1Yq)pq~%O}YHGtU0nsVQ^1Odk(5v>Y`q zHg9Hz6c>L7Ce6*wt^Aja zni{5sg~fj>7yx`{XIz7Eltlnx-ezc@pPz3(c68o6AK}b(vC=xaO9W9v?k=d;t;~ZH zcw%r!t@{26)7zOkW62vCl`C0VTLTg)4Po~KQeNOns&j~|R&_N%hUVsGUZ)P25yW?x z2CJdiOWvC?_4SQzYrkLlNl?Zs^wFFEXu!tFsj+7x5J|gx-Ngk^L)TsmLAq>AA;K-O zY-s5nk76NdUGB#UNnS{nklG-84q_uE^$Nf(D0Ih1M=EpuSSr$$#x0W~X41%@cs{#V z8oJ22n`J_H)@InN?!$HfOSO@H<|Q+K=}6mjPKJ7vscX~dftsg25Q~MrVVfNQ6VPz zB{f0uAno~xjNCjZJy&vCO3HhHQRAMB!(c^~l^pB8jdNl0?(TKE>j1cHbY6`e+*Djt zh)nu-bu}?DJIKBEbQ&l*YZ@pX1~SM@?O)C0$W6zEa104&m;ANPxx=gKXpBqQc|Y<` zkPyfo*$lPh03RT@0zs6M3nfaTY?Vy%x=DOFniH_06@6r!rrA#7)0=mDr<7}d;)~{6E__ZpcTJ2v z4L72fWH+D>5~+w8#BrK&^?XKjZ>Ee^othYr#{T{N`=eSOFU`7ju!{HmOUDzJZ0!Hj z3jmb;CT9tao;3m74{$Qg0n$JL0|lh)<7Pnc(dsKVwty2UE;m-0P8fz?peGe5BggZI zO*MCRO5{9EUHBblu2SR1x=c^&L)nZz2}_4AW+8;_B=9}WP_FJmNBvMiC=|cdy7$Ek_nl`RO#q$Z$xog z9WONSCU~Y7sLBWLhgp-PD*7>K86ZpbuD|^pU@I8)oTT2@x1nx-6<;oq8wYr<*0#3!4qvQa8sBTrCw=x0 z7!&wf1Em2K2ha@8qZhXTNM0h~NLD=W*;>uR6NXk(ntue4cZ!`bI>ddqi|*(w({n8w-1>KknA zF&0yIa**#Djzwt&=rPJVe6G=v6c90=fPi7_kv510Y)1jrkejsZ8hc+SuC{cljaf9h;!SOXMO!@GA?GyV zLF>q{S@|8E$djcOJfOM=7yyd6cTI~ii^l`oZiZ81KAR6-9$q(eqZDe9Q^(@lkp62< zf}Sj2FCi5{k?>yQPh|YeK4KKW1%YZH5Y@VD^r0NC0G6c&*pl22>bhmH#QU5B9~ONQ z`-*s~5*gKBM;PJCDGKPDh?@zY7nepZI}NV8tU*Lvg$4vUVy`!*s*5s0RcDE&oFez} zrh#0-O9-gSqhn!BO;3Z5Y584qj5Sq^tN_;1Bi(s1E*htrDPTBNmaf#S^7$HY>s%H0 zY?eAH&1nicX2U0bB0vfAb$9p)TB`PS zExkh%`SL(_$baQs>X@Vi4W_@`Q77JB-TgqldguI!82?m(c z2Pn1y?HD8f|$KJl|vzP{A7uooIZ6lIo@>>w*+!Ejc|0N z*C->QdB~yCGc`FA%_XhRcRcETnG?d`i((5v6Ld<*1)_S|CYLJ%{G#ueHRtq7oE-r~bW6lwYTkX*_<73js+5 z6SVQb#PE}os!J>90chHKq0;n+w+UUhheLn%G;Y3|6$Z=BU_v>@mH zNWGMll~3SR{tF`QJGxc{W;~ORCMRpwOtjxA=)5kx4#D!P%pn zjaZoBpET9GkUXyV;t#keyyS2D68WC%Pjqnk?P%i?e9ZlMh>JLo!7SQ+&Itm9fUhov zxspYuk z*VYCJ*bh#Hj)6a;#S|bow_S03%22ibA?|yPi;mRtJb+fDI$6A>La&*BO0V?KyM!b{ z7D|?%!!r6XDdP>h87PBW?F!3o13f+ow`dB$<~d0P+KMn8kl?BxZ>q7I zV!~^}7)~appG~t%ZJv2u@RGiE`zO324Z?FSvtQE4-3bTu|7Iy^a3j_{+wcZT;C&gT zi@8KQE<#Mq%;`y^ue$b48oc2fwke{jx9AIIE3ouP&nIghDMIOad%MxG7~fW3JOvVR z8cP~+YiX+~TY3eLtAqluOi`@~50xE>WS2@@8s8+I2Q~JZPAUj0y5YD0q4->tn(B30 zlT_}VVD;a5J1aR7KqQ{3HaD}YWAT~(K=#|YUxGO`wi6WmXR8zN=Fcbofg^i=m|&0V z>bFlp!l^lUr^IALd0l}&bj$SIfQWVUr&S_K%|2+Q{<#=`tk2hO!yhj>wFP3AZcDtw zQ?(x=rIOyZl@MiX=dcmMn6p(gNU^)*4g*c(nV+AJzWG|0oYPu~hZ;t7aYsZ#X5}y{ zuc(MZ`S^FWh<&l7r~PQ%IpH6IZPpBY-#8(lF(lJ=uJ7#SBFC!^wE4F4`K7ZvXW6&N zBu<4oWG#%ea<}T#kFm0u{(Ry*%WkwqHYWF;*V4gHq(XQDJ+}_KV8wV>P%}~u{oP!% zE8^)^uTgjSX!7g(6lj}SRBGOF0HF?yl3?*d;d*`l<$UX@?c{b@?( zaj79`(hh?e+#|5BiQz_#=LCgiMb)b4ePpH=$c!OiO{p{QKaW04i1?X?iNi<}a5KCZN!!2 z=l9-|Ex)y? zJgc0K6lA6JqSGDS>Wh3UgeQU)7S*79dz(n38sL@0W`u(u# z%;hGpRU?ofpyo}^n@X-sEKDbosL_vJRVyhk&uZaQAM*wjB7ym(zsKFpy;_t^ff;C3 z5xW@WMIpHQ(lMn~Z^fdzljl3m=fKf+(~^|8&xJQcl1(0!S5p(;*eG!5>*I4rHVMHT zDAs=d5(JR7!-vf{$((9}*4}k0K|w)V<#d~s^b`;jbdkIZX`3q9*w`!*ea_nNDA~yW z{24yUM}~RP0`nig@AT_Ot#z;6)%rQEb_gp!Pw+ULac}R)26%V~w%G03w=xPgRUY>-wvQG;c4P_|pzV=~9NfTavXid_;`rp%pw3 zm}*5BxZa<7_OL1uk(2hUk-2i05c;xGQd^OAH zcqT@eR>MP}oi)lz9W9H(8S=Ba_&Wxvz$YXMQqoNTC9Ey3J`0G8i(iPm6^&}?2S~|( z-CH*+zRs@|XDf_g3k|!YBfQr2%`iHnq{N>492Q3%O zn;C-nMEJ;(-8g`bG9hptYzG5+h%QahBwLhw<*9eqY-W_dkOXx!Pc0^Txi zao2G#K};uA6p|I^Af47Eg44U&^P=o!CF=vEtI|$R=i_tx+>|TYc;|flKIz^(nMsQK zDt3|ZyU!?E(M32yCTbkZo!J<>js<0PQ7bDHUwnN5d!e9Juv0o=T?Q{g%T=6H84_KF zxnoe{1K@^AryqWDQy4q&s0w&fLex*LqR> zGs8;u(}hA;zAicaJ^l4JXQ_Au#Wo8<`Tq4~g2E)pr8FF|Nakwo8yG`HB-XmEp%J#q z|4OI^-a#jvR<~?+=){+`F3Zt#14lb}2*QVwp=nlFnhnhFtqC}k25w=lCQpW0aw3*L zRr+z5-st1;J;33mX;f1Axr~X$)~~GJQS8UZ%f>LPMlATZTXCv34k%9AL=Gu_c@Muu zvyCHeznORZz^yiV>m>P}|E?L*D#U94T+7W4W-+YGl~81qfqm_6qD0eLC4)L+E1~jL zHvb-9ZraLI<3dtE3G_3xhLM6k`_RfVIaEVxy021Oo1Z89(ksFP4>tQ}gYkC`{MIe{ zQMPZZD5Eu2@z?K_`Bnlw=(bksT z8Ktm~bX85wjE+^bg9|93ZrX7mEVMrIx=8x*UZ#Yo5)ODt=4 z=>;l@`VQgMP1NBjD;P)i9BbO9B7I#iBN+wO;^%E-PJ#A6ma<9&A4xC>E<&C8&P%YW zvUwaEpNNbO4ibADOT(5yPAg}l%J)Kw^aLv=SzUI~>mM+ENm9ArGw-hFF1FkqV3*mE z8MoXw=~0N1ax&(%6^}0WM)pHFtCrt?)J%c0jmUTHSp?=svhbC<=YpRixwO1};AYGw z7Oc0^<6-#2*Ef3@))$>P>w-Lxcwf6mUI0N!xGZt81O$naMI$C8_y5PnuH>z!F|y5TYP&8eDa?O|5YW_?)uxVKS73hL;!rdOLlkvVC3Pk` z>ks$;8si2VdED)qsVRrP{fc>5L%)4 zaqSXT6KOh9ln7ka#V1I2#72MH@+333M^wJm)&+5YFruBANYI2}vhS=@3Z4h9v{a9u zX1KYUmfEV?Csx9hHFXc`Y`1e)t|mLV5tM2%&##S~Wi@rRHMQ|OpZEPv0#BtV9=F^a zJVggZsPVZwMpj+f|NWabykjaIE|P4=MKD?LIZxk#|N4HnS;GpQh2>)D!9U7S))1rA zRqCY=fb>63pcCfapTqH&-=ToCSfcO2lLQlE5EK8mh_q1SX1BUra09;{#o^3*_*!`8 zT~!>q>&-E#)-BMbIg`>}`gX^6GG0OX_0##Lg#*SKm&iL9;P1EP|F~Jx_a&zixZV-yS2yRqmP0?PS+51+5Pf^K~fYpk+ITKfwx6sxNv zkN+V}=XZ)#xpwXg_{h{w!?+KBSBTp#mZtkRy#}96T)G*?MV;~H=YBRZ{msV!S zC_5Hs1_9!eFj-}acL@6Q$seU9%XId;Dhkf`E%^MqOsL+j?^?@5K|pwL6yE<>(uJN87**5@UY+vh3P+0lAK)@7wnE zaB43m{JLvewc(;oiS`D~d`v!PR{qol(?Y^mD@&5eRTxQAGP%@E`~IUPCT;I>QW9N; zHag-!Ff>mmi&Sm+bbyuhF4t7>?~>t=VBp5j0&h38<06S4BM+ykmk-0YEBS*#a?Dc% zLZr9wn0;7^!J zH~X}CGXpGb?TFz}13&E&aCD1owSU5Y8^cJfoU zB0SKK`Ab-NcVyv^6@Q!Rx{Oywu2Ea+1{OV9956_!e@2x&Z+rvIP_QIP7O!_TqPlt8 zbp52>`QDIGt=-hQmBefuQ6Nw}$#9R!%jn%-t9=U${G)^Hb|l~8qHI^Rl0h$Q+_Fz+ zh8w`*cS1YjGWSSas2WaIWu{wrH(K=hv#eLu-R3`x+Zl^j(xBu`@z0p;_easWuUw`G zT7+~dwOAe>yyy{oYu1PDuSDX+KuQ<2<;(xrs}$1*jVdb(8jpm27(Qg7{?~H!uwtXM znxj1CVP~+G!lH}YTB5ZXPA+IMB#5fh`hv^!HpIK#2o@!J6+4yG4g)HlKcNiC5 zTtXz(FmGe4KLHVyCNgdbkUX4;i3)2Lkv+T^!eZYI_43+8+cmUhV0xOl2^M>I+HMs> zDVCm$PuOqf!tDI;A#nKKe=`v^YUI4-+@dbm2gk@_7E4HRxDZgW+`}?XNMt`M$ z`_;WWgX2ZX#<`orlE)@8*3+=etP6@@r*m4X5=NlHwm~XhuZAmAe*577Hb6*=#$Mbh zIX0^#DWp=bZ7xQ2K4 zC7ogU6QSV2l^AN>j5zBFmw!RfGH-`$9)M- z^6+WSmw0_l^vPvHXo1G=#zoYe=YCrP`c%_uZO#bi$)>*gN#1ta$KRA@wuNTB88jR% zm&+)kK95%(IPZOPf7Onv`mrv<8w;Z`B;;S#uvt^KUkB&;h29uHp!U+ru(5o$E+l;2 z`3Q3gc-rDcrXCufM@2qq*DPAPKu`SD&X)pf&@W$acfY^AbM~Bo&;?h%G1NnuHEGCc z-6kw*e>rt_-2D@8QT{mx*4Om-Y!p84W#*-|{CxL~(EWm+{c(NXzn)@N16fO(e$H)0 zYkU!+E=>{W<<1$7*)@9K(2wG?bki+@+WEluiLPg$Az2Y7k&G?sd87f9$Q&iQUc|MA zs}PftlFrg$eyClN3i|qAnBCr6bK?n-d9tu5&3C;ZtUm5|<#kI{F+P0L`Wy9Ao9JT` zNGJ@S{s<`UOuipbxMLePM^*84T{V0JZ$KUpVGlTo*6^LLUxh6WRhSygl1kEP^16ct zWD#2j*_k-sZ&@)4DjJ0sIRByIG}16i7CRT7E5}2Z35fj(bvuaHGz#CkV!%k1sjip) z<)pYF-i=M>pvaa>^OMO`L$BN{cMIbZQz6zP!}G6uDr-uhBmVQxEe-oowNFNcKM3`A zZA@MnV;UHx28iBAyO11f^Dg+>QG+Z;*E(`h3!+CZ!fv-7$Q-(;1Q0KhDKBd;8rWFS z7H+3yA}Rwq5EFbQaDH=9jjZqPhr9n7RyuCF|7MDGw*m`}euJA?4fRW_TGChXiLm{A zc#vp2!ie-w7yY6FmXwg1sFL^4CERyWl|B>OR^_-U6PRhRvY8#>W7<%Y%=vf- zf7R{74WAumsk&}6!h?f@lfZ_1-rCICP7S10Pe@KioRNQtNZilWO>xEG;drux+!uz&%`56meb;sqR!>8r>23`vo+ey9||JLjXt?9b5Tt^^a(t=dh{ezv}M@os-k{> zg7$l2Jnda1)K-?})9`&(j{TRkMDa)U8-o5ZLc#O=cUfYO`&6ROJ6t{-Q)W-5FBQM! zE(>_z z35YlGy+tH|cw|zjKVXs)g?%8{pLNex^ww7Vmv!V&n#y4@eK5TQ=?z`-s`3dLb@}<7 z@x{eu(s$Kna{s`KDr7wQaIBv3ZJDjzzM4Xldle`+?GX_D`}`lVCr1 zqEU;>9R-IeoHQjFi%y(YP%yPnIkmPN8m3#O?|x`B-mn4ulP&(oHDj0HGI8q8F~gwv zYvkwM)Cec9o_l+ZwSDPS%;(!jSEOqDDxW}CPkrh8P&ZY=Itho3deg+Dn~kxWmZO1` z_^nG<+rV?*sdW0)iQnO?z8q@4*vtf-H@EN*h%aUuZY5t+wrVC!{kyhK_w36P>hndA zX!HI6YeLQ}{}!}nZ0$qh_(heS-y!49EzhdYcYb^O3cpw{<&4F#n(b{Px>QG=qA#ZQ z?2Opx(DIi^7HzlAX4qq!Z&>jQ)2f%LXo&MlliW!*Ox^lA)32QWvj=7 z;mxEZhwb+5v33K~;V9=V3!sYYYV_~jFCk8-qafMzT~#<9{oXlCOkBI*gzsUSI@@lW zdS4quspVpvYxgiiWE5wubl`PT`hdOUxbC7pZ5H_Pi+jUl?C{SEWbRwG5ySpFt1qwW)a|?if4*7x-Yu6DT2$#WbV* zsRVeK%1$jam*V6Y>>GmWgL<#Mjjbf8*&DNb%oJ*Gez2~8vD<|g>~77)Z8TmPtlFb` zT~NLV4Hvy!aj>c=-CpIYFdL-LDs3lxVo@e%8|Ht~$@S)#_(#y+nk*2)MTD+%_HSIG z03SGCtJB*Fi$T=n&xiDk#blnM>RoF~9dm`LBW>NB&fUOEK?W4a{#xRycpQ6E96bId z+Cw1jW!$>Z#L)2*M(bNKy}42_%c8#c*tM>@_TD}f`HK6LV!)-(kQ^)4tG^3f>4+8E zD42Xz{|?cC^yYqjWn}Kl1CfyvWxn+sL|$yBDT&r`S<$C0OCv)tn!{1-k#|bINvwc z?Z^F4&kq_u%FebQoVQ1AR+XkV=0qwZ(B{QHb2c=1_#L|&F~JTIkg%R;GN0Z(RODW$ z=aA*pvjM^S)8N8pz;jJTuC}$(;`l3f+nf932w1M@FJ3}(`!C+wF`99nyJtr^$oUeA z%5CE>VmL@TEMkE>8)%#=KCr51qCPH_#DC!{=jh4FHI;5=eM8oP-k7bBi>JYiyFU+t zZX^7mk89Rr|3$UCRjodzy9h=CTNCqT7bDiMkL)u(1v5vkb*r;&#KygwD2$5pugNUx zG*w_i7d7Pv58j`zy56uyD4TYk8!$U|Bp)s0#(?NJ`P#Q0jdNBk0`%n4&;+2SBJNNS zP{idF>PtQ?=@{|0bADv|q10Iy;kyFW&@lLsMDa?}fB2n{!Is3Iiqqy$pks0a-oY66 zcfz!f^0Vhzyl;16;o0g-&3Dn4lEhzT#HLTCYk_$B?mKh9qL2K7ZKM?^_;uSObjfXB ziXyNwa%BSd`C>8LprthSJCr7593yqN`YDnX*NGh2<6=JCOsGDsDA&=_R&|2`XR#6g z_biYmH|7H*+1^&E{!4aE^>-F3qUor?fzdEYyv9(72vYJJ$6G&c$4>+}ON~;)X!1Tc zqN#O07gu^q2?VHM6iHr9BuK>;mG5DsyIl={N`;$ltaK{aKGx|FK00*T> zL_t)7?>$yeBrIuYY-8n$YAVX}`Qd-)JoxQhG_|`K2vlGb0lfATEH3QhuD37cqD$@p zz>_5?%WfeQ4q>+^S|0x8AJ%Z7VGn(S20LF464cxjIJ@!Ky13+`3zEw6)@w@m!O!;L z^9A|Su0cL@&I-!1TZlybKry-5g0)pgIN2SfGOwB9MVsjN=@dBYaVWzeHY^OmGtR5A zF<)Gem~^>?5n9qmZZnx(3 zySq*0tFW+eL7a-1o$aBZAdesa_)&K5+y#K5D2<*h&zB^!7e(n*r0kK>IVfcyP*qi> z*}y!%QbMz)X?`FJpslT)qM{-kP6y#o^7{CNgiIVQqJqTja^a3!>z4d!l zCdOA)RZW^ladGk@x+t>TZnE5y@7x!UoSYnTa&pqGneY@v zIWDC{3PlPjrLODJZjWHInQ0X;&$P7LYzA;BdgGx(=Es8k+%sYba296<+*vN%SuRFK zMmcdJX3A4kwH<^ZgftLB3L#`95|O>Vy{ulnS}OJR^)f#{Un+`X2q9jL-uU8+FVo!I zg2U;cxVR7@6z12&boP3)UoMx6q9U{Rd*qQH#}C(}O|`Y5U|?V%rLHK7q3ceWpPw%u zfBbP%qIx_Y84L!c!*2h7zyO$AOaAbO|3f4a!R2;RzPN=$ zaRG};3K2r^^2@t9aNu<-UR7-`D2g(K6q*nsBF(*zbVUiuL666DZrrhBhiGeSQ-u%? zX}5brW4_yUUHeKjlO;>4xa+Pvsi;^Cn94&WqM>OTT11=Gk%p&x9nM+IA5>MvZnt5x z*|3ie*4?sTYkYph~BI$&zFT@2q6Z5ZUwrfl>Mrzj)lYFaCLRHZUgZ7 ze9~^W8y=fYw|lal92p(GNlJMoz_DZPeE#!a;F@c$V(Zo|ELv2I)9JwJbfhWbS)4^8 zg25n1kGApipZ_vJfdUMt)A_g%A}AniNJ2u2kbwvrcA@E^km2+BV&|6c*s(+D>FKcr z0=OWOtINpJP%!vqDP_{R)-IQes;Wu~3+LwGfwOq?A`%I6{CEdFJw2&<-mu;7c*5y) z?grrlV;CWNF+>mOeNxI1x7!^&v}lp`+>RZF4WPchUIK>K>(vxR2`Q*us>k!eP%wC> zrfGizSd-zwV34M!W?=HYMbF|a(m_#_V@{{*r>dg#NC<%p2p9v#3}N`~iW<^1P4oNx zMzP6FR4FBg4jmGjrV$JVh0SIYQc49yQEfKIQJbplGYq3#N}0!-%s1dHPAQ}iqTg<} zKj(I5{Zdhs5h+ASfKMQXC2~keWk^*RRTL!<3)F}aVW}w6CWIlSjOeNe30?OKY%Ym(Nh$0IY!Xx< zr6L80vt9pL#6b$A0@6T8ATVq|)G0s4OYh2+HlL`2ZG zfOBf9YRs(6Y%xZC%QAg!8g%RB?d9zke&-B!ERiElQXP>=KhpQ^fyh9;GfrEp4CnqbZ4(v<+ZAfo`cVUm2AYg~+ zDlVsq1ibu^EWQKZk)34qT;bqY;Qwu}P%U(OfP(~XQo3#$U@JFIQx{7(Pft%)kfWWe zxv7&SE7-+4<3xxMXoUT*k(j%i4cG+^Xy@u<>IpJ+v@=EPP)LD;d&ThYXGu#}a~F`4 z8wl(OM=1?*v|w?ubh0-!x1=NonS&k4tz5tkKI%{J-Pm|NA?+5Sy3?`8z{LA#rt) ze;e>o1LSCKN$z3k;tGs{oSl`Am7o3p^{;0%>rK6j@w~3gmou!3|n!BazziW1-(zJAOa5Vv2nP|CMvT{oQf5s~(5xq)_9<@>_ifV#6UY8~ z)x#=7PW^}r{{S=8rL$UO8x8RMYE-#{{wvr5nV({tT$$K~KRQOY!(uVM;(<`k6%>7P z|2&nRO#qT6G-@DzJTI%rJ~=!rJy8+8n$eilpeabS=xuOVPKL|)>MGsf{)Or2wY4+u z8?FuVUrd(1cT6UC@*XuxaB<Em(=l28@B^W`Ytm{1yA4XsO=88HYCF@pAb>i!Bq7JH5(PI;d zY@`o{YaI{mH61*t)6iD`-fOzocFCiz(;7RNb4&Fq5DrdCts^5PrI8Z@$&HJfyFV-} z>?#A?p@%1KL0uNBUIUD9`O5>=Ti(ptY*e;3IHP&c(SB}zS(ulhpw^XeWVlo45E2C< zP57Fi`;JD*U^`u6} z`S8Kz`7R??-R0H>m2O#JGTyCHER!HZavHj4{?eTT}W`xft&r@&n~Q()-2^Bl3$vdn)La@wyzH5IJQz!Qu2=k+J!qns*YPs zg^7LUYGzaP=U!aLEs}SAe0M`}*ON9B>Nim&wVSewyy*#Qpg5Re$_^idwP1p`VL-g(Ne(~g3rtt8r%E@yV~Vs-HDbXh~yWWQ5xxd)YgON0o!N^~x01 z38yt0n2u8WVn!)qpZW0722fB@LlV`kXbu(CimO_o#BojnS%!g6SKB)~Q7n~- zHu@)4zf|e_s?7)Y|NNoGN5euwM0)crSe&BEhGfN&mo(;W<8svek!5$#YfT-UeENd` zo?5ZcW=1W#jQM>lBcyIE9i#ph_oLhU`A%haeBcbf9t==H<2E_kEGt zfgIy!Sy|-7gz}p=ZwCDL(;*yOTz$WP$9n&{nl~XkH=-}f%L}Th`N*6+EF83G^ICb& zA8Y8EIRssu;{cO2H5NyXwVWI>dKki&LWLBUDJi`3tw=WbUv_(Cnp%@&r>q1q z@~Q=ij7Vj%x->nMED?uwx`^b2goIWqGEvf0RvM1Aiwkw21aDTX@ZU>Iw&_JRdzd?C zo4t^W>@UESop1Fs8?_`J9v)^6Z(QE-`TV7qi6JelsED%Rl9!M`7>psa?vMB|mch#p zV%L#Ptsv&CnCOE!175$RwDhAvo&mT$Y2Mg3N|w6k_Xhc<6H*bUCmk(l!7e1R7)vu; z6;u7gc~fawDOR{7Ts|jvLoz3O7fuvfhGeE_U_g2$bZUyjQ3Jtgs}K45bUg>ssI9GC zV>yajT2@x13F+w(=W$#a8i*o7MuczsJFW0%xiJQ~6Dy5cZES7LU;|O0H8W170S&p6 z#l!OJt1C5Q#|2gFis|R4hgbWjM}Y{jpzY>AIKElBEV#_Lqp9eLgRspJrmF2s*NM%$y_}+wlJKuzUu6eAdjl(0a`?Lv zzs}f)1A%1>adsggMIln&kV#+}CrBQj=KBQT=2-DXU=lt_VlGC zea=;TOy^2$A%ju8a7m}uRau6TvNFz?_kVA!cVJ%JN%#`G1D|4p@{llN2BpM{#|hPT zzRStWhc6%V#L&4#PvMi2?y?2mDWrQJEZJ3AF4kCr4!D$HQzUP_Kl@_KEWyLjuMS)K z@V;-MO7c(d?&$=ID5uR&SROImoz>gXGmP;<=jP^ImK_?;Ti2h^b0!DZ+I^AVd;^B( zGwq&pw4H%gGfRUTnf4G8B4-{bM4EHaULc9@p~aw{Rc@O6?irbc8;U_sO%?6MkSseBpdW>*y+dPhu14@JwD=&}Dsf}`VR!Iaeh4)Nu_8dXnC=M{dy+tYxX*5;Sz2auf|Y@BzU zT2xeYypBgN6B)~+#*$d{Nt5v9JkH<3_D%M&WDPz7ue9t9)x_MZGq9=$V|O|=It)RiE6Lz_KW*SBFYo~j+6Un?C4 z5UN~f+|^x&-Ys;3_n63ZCzJMwY(w+tSG-_RE1v8AXz$*gAC^@CD>V6s2(mRivNdXv zi;d^p;QgS4i3u6t?>+{a1l;X_8pfztR#&c$kN=|6v^TFPGwsdmxXwaeGgq*7*{Ug$ zDKd!d|D?c#$Dug$$t*YM_@bq-3mapy&^u+PYmxV^$jxdX{r32Elh5Sw;K=PNtm&BK z=#_cX4J5;HYrgZD8*rRDCjLpItgZF~-@PH2ejf|QwCfKvy{`o{2v&y3SLf?;bGwB) z>=!@IRhfXFPsq?N(oT#NeflEe!X|}D z-_mu|P|LHfq?VmEEsodv-n07h3&ps*(M3hrdsVHi%^Iapg7Uh$M4Ycdqn5y09tW;R_s;YLzY2+u;cd3lsA>eMwJGmwR}-9n>s&*1S={O<2ogq>@*e z##nJA@b*0^SD=Yg_iIqT*t+)yw=r1pFb=g0#p~4ajhq>?&q)GU^Vh4J&>cbvfu zI9`94E60i|TVfj>bU%~cgu(ny!q~8)`ejb2ngGY~s&{Xr>nlQn4|<967R;M65wmKi3I4sGM*=OCu6g-6Z#}p&4kFu?9h)pT>}(?`Xj&y@ zV=5Kgq{TVaCkiR@zr=1gmoJo~xX->WH_^Bi zvv@U_SXCCJ9eO~>In`d5IPA?dFbgo^!)}o?J=eT-nQ;?}U#=cjclYC^w3@6gDd%QC zCJL>KajylZ3Q=bi6Vo|H{` zXyp;H?aA(PjN*J8Vgt{f3T=!TnH7^Gt>$mx9vZ0 z*>vM~<|6@MPdN{fb_Piq_nnRwizKDmo3Kzc7kF}27Tn;xpQ9Fo3h>>VUW9S-s75nd zc&R(SF4kptn4olN2L~2l3|jkmD(qKGs^W z^A+xv*l?xq7Mf^in8$BO&Xd#mO6)dMTL19g30bh$E~v~$g=NS$P)e_rB+$t+RO^=8 zv`lnuU`*NIC_$&(vYH?ov3clyTLKcf)shwT97p{f}vw|(*zV^LLmd#mgF zy2nk|FF8%4c>s0xnN@S;EFxNE{NPM_QB;`FILDmOcOs)wD#sXB-PX(#AdZeBZ5D&i z5d~$8x$0Nb!!vLv3?Zdm>yXD%X9TbltGgjPEA?(Vsj2H*Vd3ZE@43qru}K<^KGzsV z7g#s5VbGAytKvwo)#@@!=BxRMtS6fMK1ij5p+5!_L(X_NfryFd~n1%dv8c2j1q>DQR|Z^0iA0 z?|)PLWsnd^JCXTbqud4NdB6#r*6%jsAi&U%RN`940VI$4@kl{#Cj$u%CCU}iL zm>fs$&G{k=O5E8mf?-B>Vue^NQ;$*{=wqUnqQDz9SU9bysVK>m5fw+&E^DClDwi5M zTq}$JbV%-J#HwW=CYrmQC?4My_B7ezzGk3?u=0Y zp+ihVCP`e3o+^u8T}CiCHw=Y?lAi*1{`*l&NrJQ)A=HVaj@OYb9#o?61ooY}(9-K18FygarF1KZdPxye>9A14^ISXC;_ z8;+(#{jO!uvR28nvbmSR{t$oI6?9QhIlm}6X4a}Kqr*E@Y?_D{VaxTnCaPN6)8RBQc8;YJG@Zu z5&P$gA34HNta9|yU!60+oq(k_!zQpuozd)F%hIwPRiF{JT;Pl!>@ zns%V=`xB+eF&BM!<#X=S4!M~L$EGVTFGu{@1^YbP1Ak4z+xG0+<52*CLYF7Mhz3J9 z`;I-#)L3*Kv^8hV_Vd%JA#$NqgaBTgYAVPdl+mgebnT}7q%cUn^gW#%(NNdqYbjv> ze2Fr&c|wDGKI0*ro!fl_?W2liWLi2eI9qNeflj5y879qHXMQ;nL9G^cj8p6w`sOVI zV>KpP7;drn9beWk{?wGJq#& ziP4FqAL8Peq5M8Gr$D-BU_c~}1n@kxTG|wdN);ma>Y>`}{>~M84bjo)t|zY=m&XC% zNPCRzPV1$iG5kFk>lX zo9T}xVcYW9%hh+FFMS>S+Eh&~I6{>LX%=ZFa)29WwkN)D6u|3>GgB%o%TCl2cJCZ^ zPoJ z?X!r>HWC5?LNSmimildsBqjPJT%NwY)Zql5GiII$G4lxGQcqBjO?-Vt9AGXD>I_7R z93N@(zU1?SN$-y5`mr@@X7CY%U-REW;E}8TtD9gBrf&6i{J6|8f1S*4rAYR41`H2RRDCSkT#+GF2IcgnNeb%${I5f#7$k}q+|xG1I_qwz zD^}$aW-N~wn?F-COUZ*+%i#w81lrA&4P(<`B_%%FHo6sa zbFl&wI@YXm89ynR4>TKUiASF>bc!WU|m~awJ76 z*PGuUui48><1&{_?BzV4z}GU1QGg19zYxPJ_82Gfs#O>AHmaBf=MLjqgl!Dd46 zoU|yt@0^6tWVVFP&8XfD##6I68Qk5pu7yHPIo*Gs2EIJ(-T@R^t@owX=Rc7-NUrVJ zNyr*Us@-GIzc^R-8jS$o^8C0bij7W3QV6g>_BYwxsoNcHBS)AOJ2Y*CXhQZHuq7}_-S4(#%t0`()@zw#%?}h)W zrpp~B8#s!oB_a=VV_RfKAZAYRBwZA4{cx8bp80bMa2M7&{&PZ=^e6zOV7l7kzT4zY zj=?VDPt1e5emAq@cl33>>GXigssk(_4{}QUMLVZrh;C}V;C9X_y)!6s`<%-@evAO% zB3gW9GHoM0jjl#fcLJKVZP~erEWzf}j)$>zA|Cr8d@AlNh!?AA-o>_fAJi;6{o0jy zC$YwS5Z&Ws1(ZE8IcYr{PXmx0(BHqmKo1Ja%YOhA8FUgFYwUF6%UfLz`5x%|xsd?* zC)I*E%bN(~+{-=QC59ogo}Id_UwYsBxq^B*#Cthf9=?Hu?-6lc@fvE5;;jX~(pIQ( z2HDzfW&56R1nOvOyF45>#t5Yh3#X=0ZYyH@))Wx>zc`O_qONZ+5TyC+rdb0#&d15w znHg1MV@Ks9szPcUlr)VeX5C+3fV4`8G^W{pQ;=16EcqSk-7w7eF2_0sL;0K_iN5YS z*yebc^es0bUPbA~iNQo+CF6l1W#M)d@7ji)$wT_V%&|vn^TSE2>qTOEIPG6eQ+3)R z;?EG0169j5>xt&5{_@Ef+s0+3cv|~n)|63d2K=nDKJ~cKWR_moxvIK)55Sd_R95n| zS7v&k=J?(4ulPs_cluw$E#K5lFC;&39fWv$uo`Q1N2M@ZuEzhRX#>1zjOa6;=>1fT zVxx$bR`XG1>sXfF$-&@bMrmuqFl}|DzvDO}> zd%A<qr*=|NWMdSBrlXxFMCHdbT{p|k z$i!5wUxD~dZ0nq_`*UnZhX|?Pnb=&pUN1oG(lav36Lpj`d$=yomO(U?JJ%;`Cq+h| zZq{>n$dc!eb~JMC6Pt(n6p3#3^ko=7U@vCT1u05?wwUm@4Kc%AdGveo=OR&3_Do1g z8I1VAgcKrfCH3&|zz@)oB?@&-t0#3I?j8d~fwb}qrb)f;jUzx7P67>eTRm9r?(X=q zCgeK*_N8Zo+s@zo)6Dh{59I|roi@cqo(@zrG`Tu7M(yS2(waOz4ryUQlC2$6iy%WY z6VV>ZTy*d5q@<((@|Bw9zOJ@5Avrm@E`pyJJ(; z(PlHi?P_2!da)CVAa7<|+Gk=kuOY6^)w9X|aD5EhNinf{d42*_t9;(i|HmITuKCz4 z1%W^@J1mTPMNCpMMOo0Sl4RK6{^1|?Kpjm@RSgY*v`J3J6%Y`Zu2g6mqw%?k$YbZ? zN^DS<2S`W~5)weSbB&%}ZS}ka=ok3VkqwVlAmBBvI{xtxl#q}>Lr4Dz%<}Kw7y#v9 zr8{Z^aFP5gE~6|EY)?iPj+4Eh=FgDy(xMrQi?~|og-T9wOC@y13*V%ZBdHl92+;1- zH8myK@ezMSkO=!Ec64;q*`cDK=+;<-6L{Fy>k|+Y7ZeuuD<yus{2j| zG&7f8DP;s4VfUs}YPavXS0<3&#(-=`M@EV(D!7>(8kY}FPkFD@zr@F5tvz2i zQU!M=(L1-w_S$=R%XRi}YJ2 zaB113IAvVNs3Af(GfsSCo8R6^Qof-87T#zIn+%fa^)^);62Mx?6V1QvZKkS+ZM!t{ zd0$v8p?Ra?GH>*tvJrDOWP|Hnp0kAwtF7OQWkg+BS~eN7IyP;-!I3ik{P~M4bd*CtsPEW^g znCByRXn`vTl9-z-M);nL%bzPtnGSFWvI(}p3X=#!FHFk`#+aF%Ev#@p^k`MuJ3u@< zIvVFL8t^qeu}K618C+%C#Yp*OlGUhrDPoqKi*jh6k&)5kqxH?yZzuAy4q=kw(vdtV zcfT_**!x)Xz33nX-wGD!%ap@IYy9D22Zuca6AE#MotL~J8N{uuM+gp=yK0G2ev2r@_NeV zM^7I7#RcP;*NW~;Tv}rY9EGa1_{awe462H_JbG!Ow0l7smg!W({Ho5J-Cf*{`=p8$ zr{314yX2cp7fwwcMR}R1K{GB=ehb_=tJ-R_{s^vk4^L0m$J_Hdltp_U=nuq!Z=QU_ zf7aTU6VbHGk|NnUQcFuq38prcUprfG`LP~c|5+S;A9zcZsZ3`#$4s-H0dAqBZ9shG zDx7_+0HcflKeYgc?D%F6u9KI)CEmk^M`0wVO#($O>5On=@>PNA&&A_|F_gQ$T-wOqe`gc?N2V>_8G{2$${W9TfU9j`oR?efuE@!E@Z z&-MIrY?h1*2j#q%>=EEVl4k9+qbWdJ_i5xMdGucGcZLrWcJ!>QThHr{$(5BS1hu$| zZ~3uj@v(2xI(h9EK6!iddwY8WU27N^*o9)#ZCv>PUYqybe)vAr|KU3A-oezALdVGc z1K_^&kQ0~&sEiu^CJ2jQR=YOy;4x$_G=KxYJ_nGwN8*|_E*B~Fg-_7jZj(N&Q=IIDD`1;7^2n~m_nmrp7xczce^a+*`yLxB4)iAiUAeLZKFaPQp9 z#?eukNXMkk26HdV(|GQ8^ub|C0>!H45Kl%{Wnj~Tx#6!7uMS+L{62!sp-qI$*7HXK zs(k?a`J$5uSWM()-IKZ*?R_JABo7G*$rJ*W*IQQW(o&n-I++ak#Q0v_4mHn%l?Yyx zNl;b%zJ8WniX!5z0k4bHA`g#_!hYvUfOd=O?dH=V1sYP*0GG=N!lY+#sr3M0K9r2xu zcyQ;F2XXZ9I4?K$T*v|W@>AH8(Wjl%I?j?vc?RULUWjCfMW%rnZpL{KHK%D$KP}{I zX855KAHa3>!8q<89sn5s`T6ker(>{|#Px)Sizy-mL?{b5UyAm=H%H`;Q7nn*c}ypa zCbOdiRKLZ|$=17e= zs#Cc&l=}@4J^+Z!fT}s39^mDLpEJp8inwPXOQ=8)^kmnonQ=d}9%~o}WV6X> zf7O&;4*vcmwB`|wbFLL6o~hDP@b1^8gCUkvWt9Mtk>fH=8EbH+S-v5Nym|X3R^7~# z@7MA%&WDt-yRgn%shQT((75O&gLhMGfo5aXidiM+NCKpC*n!wtB~z1v zQ-7_Gu3{9lsl;{@pct&sbdPDCh&A`n z&VpM77F0=)4}W)jVB1iSL>N;ZFFx+O1_j7$h8;IDDy}pfw&?R@9qeuUF*SlKYj|^J zaUziCB*P}8<2vv;5|B-Sg&QXNi0RlE$;4xyscDUZ51olgF8)NQhHWV?J991#QNAi( zD`(+AuDwhe=UKEe(2o&G)?K7=Zv~LDQuuWrOhsK+_fx>LuIP+C7B0TT*c2A`)hhK+ z`Vc3DT3T?lz;bH+>#5XNt}}*75KgIS&FKR9jy@|PQT_wcKw7hCT1Q4{&vL9mTEV%T z@@?vvy)O(hxyp$AwgEHYPNf;~hNJ8T(*pIi{7ZA03vNcd5`r!qf2^qvB(XmH*cB0* z>r>=RI980p;kI*HmxRv7gy|hCcK=~oENZzC)tDBT^{S+gxKpG1ZUgD{>TXUgsF9mg z>>CfZ;Q}a!1^b3_?F?uk{Mg}R@ggG^Ucp|8G(>C@Kt!s3~y;-KWeV1Aep`qg7Dmd-gtg|pJPP{s>GVLt&h*i z0Vh*k8G+Jy#OInhFH+ojIzgROY2M+(oo^InDrEP+BLhVrn535CgfRupvYJZJ+p{oH z`|A_VcW>Y_Z9r0Li5$vOMX;=i!wcb9Z{(cXA(BWuHnT3?*lMbzvcF@Jh73FS!;#sgkdG=m zXcLHTN(ReiXEa+s(~iB~Qm#i!tIQZ~lg@8y`u;v}`yV(y-%e23ym_!T^nsiVnsF>G z3nIUf07_iknT^s#JnbFbNmRZoz2jUv;*}G)@NJOePatVnoUr>iNWKVae!OUOz1Wr` z_21?oy*)nFZSZ4|k_rJLIF)ojFJIMx{!)k7ClX;xlMzHcjT`QsO;ho1jBgSFd2#d^ zY;9i*)^B(@FPN?17sFJG&N{Fp0@S0~)M||~Miny4yvP4m_c^m8J>&$vAj)iOWlysL?Qt+|ts*Kj-#iVq&5sYA~il8c9APQm?K!dZcv3c{G;4b?VMij_=a^Dd8JGYnItB zWfl!`j4s$YTq;jb^Yqw+#WSZ`vLTXzwzj;U9%#-jtuhS>dZ1FE9Gx>R)y%KLN>dZx^Gc-c{Z&g%Qa~JD5l-fjxgcbDV0jR z>pEF&9e;{&&PyozR*uDumrkq8fUVrXV4$W}t#<%KutF`7Y9ui2*c*`518IT-k1K^G zk0P~L5u+)c#M+Fu+PwSq@v`-EWqG+7L`j3)(eULqLo!cc^?MZI)q4sCW=5{g7C^d- zCJ`L_!-9)S8nc(!^h1gEPHWJ=6VHcmq-M6INxa=q5%cHe8b0qU;x z$6a0kkM0?r`rvVMbL;82ibOVl1ImDaGO?zAl?ygD>@lbmP4^_HvIg6ZJh7L=&tDjX zp^amS%5I6l8098`=$3^$0Kb7Qo=Yx{1n6ltHa4G-!~on2~yeD!5Qa{F`Hb}nW4)Hvg>!3vVp)P@3J?S(~ zA{-*o({^{+e6V`DIjds~sXmw0?*MXX^JE#7U2f+qt4J@-MIf2{+?+X@OpCWQ!G$Ab z3H9Eq2C7|aE3?uGin@Gl-K?$cPgUWjAJ;eLhng{K_=!E%8Z1#WCPZ_xPaJ)GeGiV0 zO}q9u5mwZpDnw8&C8g_I-S{X06_223<;?J(`GIs$3+AmK-DYY)pX`lO z;v5lT0u`~+X?!6Ty8-xFk#4^P-c8wBx4|A8v4?--{%-M2oREdB>gF znwp%kZWAw`|29dw#ZcA<*O~)!;NXgGm`;X7;ZM5oLmU@nZch3(;tynyv@GZ`fQjqU z6&37XXl@vuUNNk4yqKZR<;*Ik4wE7Do|K>;=iDmq_t&FK}T5SO{e&eupwzv~Nt zSiNX&Rd>R-h;7T`9v>kujA}m5`wzwktyrh%m^Y}+|q`ULI(7WMNahOQiY-G=huO~Oz z^E6xsMV3Joiu0)Z<=7>OaJ)=T$rpEvF;v(BFUg)^F=94z|+HmvXY=N)&lV;tIk$n`M8m3t{dUbpFUc8ott0 z@o2q!{&u!CK^t&iHJm0usdl^FF7XFk0~h`mmoQqa_xqk!M{6&K+vj9-PoSq)QFD%OJDvmJ z1DK@x`?>1Tpi5aP^~PVn;<~lNOR0Sy*to8`=l@**AKo9s@<-5ikIE$ceCNHVYwzsk z{vl8^DEw^8HuZ^0RS7DWrP|kh)VjtVz652v8%lZli>3?r?QyeMejTH&T4@iWuzcG? z7q1XR3dWW+Lx0|rODbbKu|6<^!4k3b1z5g>^vV!g{V0ZZ2TP96)J}#JH2sJK4s|I)o& zc$OwrYCrOV$zrbGK8tmD%|~$D+^;<`p0=p>T8)#|CVgt`3_5+eK=KT5S_}q_8iHMh zmnu01kCW-e@tNwM{|1Humz@_uKdO+u9dyN`-)h+Q`&XiBThQsFK8yq$Pi62}hTKlcT2xu&-ZI`86_a73>@OxA!ZhyoWTIIDD~NOZ?e zvzb1RPvfpRF9y}waf5bpI#wsZ&$aaCYp$?g71zuC>?l1mGvbDa60A2zuelXv#+mWI}SH@*F$Ud#Yo z(vIci`EixeH&2VSu|4C%?a1}$pF;tp59V~I9nV6XRW@j(KApL5$_>*8Mg1-uV9DmE z6u?b{O5SXH4D~xXxk(-E2^7NF4HaxX3mLhcsM<1Ymm-73d)C>#ig`TXn>W$Qptym? z{6G&*lm3DApmDxVJ=$>ki{oXtXIjG0X)|QkSxW16aemcr?=s-|v^^!anDK2ifj|wT zxZmG)ZXDbXX$M-7A(MV?6mZU~!`CU%w9+JSPQ@Z{&u1>L9Y~(l+9xHw@rOl&q>wp@ zCt=yA#0sO<+nWVOWKeszze9;iMfoyxSe&dtvQAe?K(^q!zS(cE!Tm(vXsFx$zH^}` zrqR23v&FU6w^wDGf$j5+n7NW|RYh7%z?nL+a#-5jj)%)peJJAwYSQ%5QhKt?*4^V? z)oW*^oZB_%BIJ9fkWrCc@ua4)5`szB?Uo&51wB=AaG$o8-bBmQ(eULq#h2BGD6NM~ zTrvgR`KV#Ao>2{z`(H2m1vX`m&D`7Z#%8}&y0r5UI-ZAU-=aU}? z*nFD?{jDb`MfSaIN0p`lR~sUTLFRN(F;k_8x@}&@J*D=~28{v2_3n|sijz6^rgKai zTnA2t-@Q>Y(k7d|+>Mdz3~=X%YpHW8t`=p9VX-4plgjMg{P=wQ_AL}hM{lz4J4?*x z_GHFGKgp(dlzX3qlN4nb0Q$b`N>k6zB%p z=Sfbh^12oySy@&dR-c`rrIbNNS5b>^{6g2379A1|er`JZ(w6UOPOXCXE0txe1o-|8 z>#VLGsR;6RPWMRJ{bv1uKauH`l?nS?8S?I2z#M|gOY>E|C{;b&3pMaZ+Q3Z zyNN1xS^O!~^M@x$K>8=oDrNCGt(2%^C%@bFNUz(){JICmyLmF1PZsmSETtQ@Wa@V# zH$MwKMO1|5Q7w!E{5w3^Oj@V{$Ij!Yci?6wctv_r$LR3!k6f2m*%+A8JN%o=+2sw` zZhO;KPX&CiCM9cry4Z)g92KQFjUTt84PG|yEf0QeE-cID2}e=g;w~7kzOJTjI?8^< z+CDz`^5iVoQd#R#LJ>u&|7zLfgf!t69kntJr;V`q8Q+Kv=bmSf-t|L5~3hN?yN z@ry%kIOBzcv;w%&{+>|R34&Tc@Phm0Qk@$w%i!e=ZYcoUPc>ghW6b-vW$3J(MHys= ztMX2gn*@4M3>w@IWCm_E7aRgr@jSbJ*@Gitm7D_LhjcvUGUnQ^Q27~8W3%#`#p%xA zbz#$3ad|I$-yZ`BJUwbe57%w*U6y#;3D&&no2P511%)hDyR|^1R3ZInHp*mJrD0-{ zavrc($zlnePT2LQ?U@(R2w}{Fx+ogge9Eo)t%?wE7aaC1CSiT`mgeQ$Ra9NPaZ-6O zJWHb!+385Iy_hnB_So;l#Q*l&u=vY!8vW$y$M0>wHnd9j#z#{JW!4(Mj|8FbZpGSP zQ_N_n&c(D>Ma#VSB}RXhf8N=9{rG2!)GR%zL##LTRI}ClMvGKaOH6AM+IV39P;EhO zI5wU`U}by&H`NqU89=12|BF#<&9@(J_EP%CQog_u-12j7^wG%~_LQMjdZKctcN&Ij zD|t-Wq~I8K)tJI4-PI!3&8+K=%z(T^s}}4zu=XF-%jCK1IzR93m+MmbgF+jz_w^iD$>RW;C2cMvw=g44nk$1`eSh3C;1G zv{ewMjPeVha=rw%K}YFcXchzUZ`KkXzgU-Wazj1B$Cd-v4J3`65yGyUO`vq5&uA8mL3A(*+Y`c?YScKGz^SI<;f9sB;5nk@2t?kJb9Ed z#V=<-M~XD6T3Tb^j-#CeYvY}$CxpLuJ!5S1Udthox}BR(=3}49p1Wu(o693bg&*(; zV+N<{$rW(*`K|p~?B)Z=S&oaqSGC|5*5n!7g!{zjX9LR1b!})5Xv$wC&D(UsCz~i*!?QT;n6I5vcy%F!mwLD2((A*@-x(Vn z@~+YOC|A1SW#?VGvZV7;s9wj=#On-g4TF?QEdTQc^Gtg?Ygo%t-DBr@h}7dGI7f_9 zufeN7)mMc?V^U_t_q2T-PUNj>?a$Dosz5pkiB~?pMMWz){dzw_myZkD+Jc3BuWMi- zoj^rezd#Hz=#j18jG%%3Fjh5*RI8XoeBY?0@;!Y7Rw?j2K+fF64DiTTWooRL&ewHwiGFt`XRa?=F?8=&r-wOA;D{=<@I6?oZ!Qc-9e>p zQ8MygmMX*yh+2g~A+s<$N#}RyJO{*lgmjbnzuJ^@9gXj~5dwz4LjGQqpd{ikX(l1t zYuDs8D;2d5rjEga+|6a;?%&dcMbljxcN)qO3HV=rj~2D~Rm^VkE6*{Rt4)J`tOmpV zByt8;A&|3zI|1-iY-62%bG-wza=x1lFNcNIv*V#l2#>exJcWgU{(+gT9ad=gIKDo2 z&`H~m6N+>+_74HEblLOYqts82?B3o@Rwb*&g4xeLX+l4-4^-bxK9i9R zF28$w6!@qr$lLA;TDofw;}&^{GQGT6H}X&H?DQx3EQz&pt|AefKTuXN1m2t?W69W_ z5p;bI4xiA>t`8BiLshPSOF{hyyeomG_rAD+kypGm zh&pduB6HS=HWkQhx{^VJ(s5w2b1KrfLV36-NS z7Ve9ucQ=!0=NmWLm!dCNmaF3C9rM@EA4#8Jxg0l-7hx>`OuD@57Ztoc5H>yBBSF|W z8;0-6RbBEY^1%>{`>VVPVx5H>EDM z2moSsx36Qv))L-np3Gt^C;HUnlV+VC^@;K% z4^4Znc(n&@muEihGc5Xjo}CTZmxmr_mG5HIjPdbZV`?s3Z0+ny4C=n`jHcA?Y)R68 z-|h?FrjM=cg)P6!tH^o5(&i4Lb$I;y6-F@XsPWX~@GZDreQm*&_*L6&%VwTV@;nG4 zxC(E1f8i#SmwiI01R2PmXn)GHfLqQ8^M^rRjIn`v`w?pN*4 z0`@!F41?OvUlYc1y&SzJe|zdFMijD`OaE-x_%f(GOYOWo6vwe*#Q#OdpF;XjIDB${ zDM{1!(M%bPEYQnu+kDH8M;=B4Mpd^Zd?59)!v!~pV2?WMXVIc$(w^# z+c*{1AY7Xd8uLeS2&GbjC)x$?Et|MpgvWFa3gMzD7_T^_=4sFT-MGeanc{!FP$7L6 z_;jXArtziGff4R!MQ3K`pN|E0UoR1*q@bQIX$tt(ki@iSMC(ZbA^p#P@8fv}3Q_F| z3E*_Na!(sd8Rfp5<$BBoG;7YsH zg=>;3S{%ZG9r>7t91{j7-QHmHexchzv98gYJF#FdyWyW2x)~Zp#UjB`U@t=iM7tEC^}n0ZgYlZLhqw9I)WISUAvjEy9Fvz5_B8Pa z+(}M>0FozZ>Ylr!74zw_s6dTD192G#zTNJ0yk1^|Q=rWtB(r zNu8JFSfJB~OV-!q+L9Cdtf}G=n#J?HDN2nw-dof;*Z1_&9NNH|)ypyd{P9S}2}X#|)A$bHCosmn=0pK&U7pm;CroakZl zn*0|-z?$nS7LQ32e??mrFZbni|Go7jKlu3z9BuR9kIu)Y4&t%4vaqa|kG_8$>o&X>fZ_r{kv$>S(gO+q^-Ih7 zo4a-q8rJ#kV*x6wp~&7tv7?D~>u(xU*S~#tHBY~=hj={B<4*;-^2#j~*&DDagTO{s zEV5Bk)IcCO%*vW>Y<3$JB>{@;4S1|=AlA(d!85|Ea5y>qD<$!qF1`2Odv63D0#Fo% zJ3etcx~|jFJ~q;GuA!%=2VGBgoGhwJVNp>U@e*CQU@%A^5HQp9^z;DW^?J>zZ&DGD z#pvrdf(Z)>3ewC-0P%R76D=+1y3V}$^E2j=SlKSq^}#@ZK+uqSR;!g*EQUo@DK06= zSl9mkeqym0R;!hwq9QZzl9CcsRb^;sh;TTJ)9EBXKOarg=urEJ-qte0^rE7InJnX3{FNgw&yCGyrK_vk zR51YpfnaV#9r^om;=t=Wcj5C5;B+}CE-vKskCmR?&h*Xgc2QVVfTrpE`Pt`4KuQ_$ z`~5v6QVOI%NFj8oC<>~on#OkpK-09Z0K+5uJoEIkNGWl9TvSz;;r2LBcU{k{?JNMW z+ijGU7gJnfjFRo#`8vJ5$q}}`zP@Lrl!i+h<}#)d6sc*NjKx$__qVKExl%s(;De3z z_4V5nMfqod&dx3#{{5p|e#P6#%gdv17>7dFc{+a@#a%k+p~DfAsh}LK7PFU@!{cNf69c=QYeas5OD<&RS;1j z^jJKuYc`ur_xXI(*Vh|EsKH=R0=lkSwOC9BPqw%J!0XA|TTtM=!(y@2kwVzBIE%?5 z9*_6+_VvBc-qyYsNKCUYg|X>Eh`1s|6huT9GNMQ|s_Uv2jYjnmZW?{mty{M$-QC@m za5(G$ix*_Ej#e&py#z#w%jH_+bl4Z#Z1!p)gzaqC=q$#Alv0mGqCLT2uzhfFuss@$ zh5>VQEJ0FLQ8Y!h#8g#;6h#?OgxVv7(hZ^y;)717bGWRmEWUN?R^0;7(9j?O-Q)4Z z6-AFoDZ@gS0U;Eprt7wV-+y#yaIjU=G>a~!Ds^3qtU4{mTY35{&H^Bn#19U06|pM zE_B_l2*n~5!`>$ooOTmzW>K9TE zsTNCQcz9SVEG*Qks;YS4fd>$YwWDsn`DOvAWo2d7a5(JJgvb|C7D_3L&?(TRo+qVr zNnN+;x^4j!T}lN;^5B%t@NyPs00baGjx_mFF+9?Bp{Q|1AtDqtEQIhYhyfu)KM0@2 zB8F@>Td2FcI|gVEKKP)NQW~A91X(}!v5)CPLql;@RU;Nv4N6dSArOkxg;e6YB#ICY zp(r+_v?x-l7(^9w!ae6K<{qS!LI}eIC4|wt7b1#aSO_J6kV677DE?o2XOG)95Jchk zW=V5xFXz>Y>70Jfs`hOh;&4Z(Ij`4VD0c3tOpcXz^7)cz(Ix^e+* zKA#77&&+HBU`lf4?lUK+kR}FXE+rsMf)S^s@A@m-|406HPG*acAQBGAK@I?Vk_SpJ zlC@@PLkKUDI(I*Ax7)Z}F1@NMz0v0TsQp^3d7j&JI!$AYDS(N)Pk`|X>A_D+ z>gWI|aZI_6oQM!91LS}Vh>}GG92wb@@j$Wv6hIsm=5q!&KTgI>g1*ENcwVAC|VSS+k*q459v&Waxn}+mpH88kALuMtG))t4Zf?A; zYXV?V6nK7q=59CTVgYnrcb--HT04(Meiwrz resources/bttn-illustration-down.png resources/bttn-illustration-up.png + resources/bttn-illustration-color-up.png + resources/bttn-illustration-color-down.png resources/bttn-save-down.png resources/bttn-save-up.png resources/bttn-flash-down.png From 577b38b78629ca3a66cc38012e3949ffca690f10 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Wed, 3 Sep 2014 04:31:39 +1000 Subject: [PATCH 112/203] Text for AirSpeed page --- .../setupwizard/pages/airspeedpage.cpp | 34 +++--- .../setupwizard/resources/airspeed-shapes.svg | 108 ++++++++++++++++++ .../plugins/setupwizard/wizardResources.qrc | 1 + 3 files changed, 128 insertions(+), 15 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/airspeed-shapes.svg diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index 4bc0db2b8..9d63e7754 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -29,7 +29,7 @@ #include "setupwizard.h" AirSpeedPage::AirSpeedPage(SetupWizard *wizard, QWidget *parent) : - SelectionPage(wizard, QString(":/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg"), parent) + SelectionPage(wizard, QString(":/setupwizard/resources/airspeed-shapes.svg"), parent) {} AirSpeedPage::~AirSpeedPage() @@ -44,26 +44,30 @@ bool AirSpeedPage::validatePage(SelectionItem *seletedItem) void AirSpeedPage::setupSelection(Selection *selection) { selection->setTitle(tr("OpenPilot Airspeed Sensor Selection")); - selection->setText(tr("This part of the wizard will help you select and configure " - "flying aircraft utilizing servos. The wizard supports the most common types of fixed-wing " - "aircraft, other variants of fixed-wing aircraft can be configured by using custom " - "configuration options in the Configuration plugin in the GCS.\n\n" - "Please select the type of fixed-wing you want to create a configuration for below:")); + selection->setText(tr("This part of the wizard will help you select and configure an airspeed sensor which " + "are also commonly called Pitot tubes. OpenPilot support three methods to obtain " + "airspeed data, one is a software estimation technique and the other two " + "utilize hardware sensors.\n\n" + "Please select how you wish to obtain airspeed data below:")); selection->addItem(tr("Estimated"), - tr("This setup expects a traditional airframe using two independent aileron servos " - "on their own channel (not connected by Y adapter) plus an elevator and a rudder."), - "aileron", + tr("This option uses an intelligent estimation algorithm which utilizes the OpenPilot INS/GPS " + "to estimate wind speed and subtract it from ground speed obtained from the GPS.\n" + "This solution is highly accurate in normal level flight with the drawback of being less " + "accurate in rapid altitude changes. "), + "estimated", SetupWizard::ESTIMATE); selection->addItem(tr("EagleTree"), - tr("This setup expects a traditional airframe using a single alieron servo or two servos " - "connected by a Y adapter plus an elevator and a rudder."), - "aileron-single", + tr("Select this option to use the Airspeed MicroSensor V3 from EagleTree, this is an accurate " + "airspeed sensor that includes on-board Temperature Compensation.\n" + "Selecting this option will put your Flexi-Port in to I2C mode."), + "eagletree", SetupWizard::EAGLETREE); selection->addItem(tr("MS4525 Based"), - tr("This setup currently expects a flying-wing setup, an elevon plus rudder setup is not yet " - "supported. Setup should include only two elevons, and should explicitly not include a rudder."), - "elevon", + tr("Select this option to use an airspeed sensor based on the MS4525DO pressure transducer " + "from Measurement Specialties. This includes the PixHawk sensor and their clones.\n" + "Selecting this option will put your Flexi-Port in to I2C mode."), + "ms4525", SetupWizard::MS4525); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/airspeed-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/airspeed-shapes.svg new file mode 100644 index 000000000..350e30e98 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/airspeed-shapes.svg @@ -0,0 +1,108 @@ + + + + + + + + + + image/svg+xml + + + + + + + OpenPilo + Eagletree + + + MS4525 + + + OpenPilot + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index 850bf1f05..8b26ebdcc 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -37,6 +37,7 @@ resources/multirotor-shapes.svg resources/fixedwing-shapes-wizard.svg resources/fixedwing-shapes-wizard-no-numbers.svg + resources/airspeed-shapes.svg resources/bttn-illustration-down.png resources/bttn-illustration-up.png From afeb464eb6e33dcbcc8db42bc9b65bdbae049a95 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Wed, 3 Sep 2014 04:41:49 +1000 Subject: [PATCH 113/203] Add some line breaks --- .../src/plugins/setupwizard/pages/airspeedpage.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index 9d63e7754..3166cd735 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -51,7 +51,7 @@ void AirSpeedPage::setupSelection(Selection *selection) "Please select how you wish to obtain airspeed data below:")); selection->addItem(tr("Estimated"), tr("This option uses an intelligent estimation algorithm which utilizes the OpenPilot INS/GPS " - "to estimate wind speed and subtract it from ground speed obtained from the GPS.\n" + "to estimate wind speed and subtract it from ground speed obtained from the GPS.\n\n" "This solution is highly accurate in normal level flight with the drawback of being less " "accurate in rapid altitude changes. "), "estimated", @@ -59,14 +59,14 @@ void AirSpeedPage::setupSelection(Selection *selection) selection->addItem(tr("EagleTree"), tr("Select this option to use the Airspeed MicroSensor V3 from EagleTree, this is an accurate " - "airspeed sensor that includes on-board Temperature Compensation.\n" + "airspeed sensor that includes on-board Temperature Compensation.\n\n" "Selecting this option will put your Flexi-Port in to I2C mode."), "eagletree", SetupWizard::EAGLETREE); selection->addItem(tr("MS4525 Based"), tr("Select this option to use an airspeed sensor based on the MS4525DO pressure transducer " - "from Measurement Specialties. This includes the PixHawk sensor and their clones.\n" + "from Measurement Specialties. This includes the PixHawk sensor and their clones.\n\n" "Selecting this option will put your Flexi-Port in to I2C mode."), "ms4525", SetupWizard::MS4525); From b93ff6bd89a14e2f0f9749283b1e79e20f5bf12c Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Wed, 3 Sep 2014 07:16:36 +1000 Subject: [PATCH 114/203] Make a start on GPS page --- .../setupwizard/pages/airspeedpage.cpp | 4 +- .../src/plugins/setupwizard/pages/gpspage.cpp | 76 +++++++++++++++++++ .../src/plugins/setupwizard/pages/gpspage.h | 45 +++++++++++ .../src/plugins/setupwizard/setupwizard.cpp | 35 +++++++-- .../src/plugins/setupwizard/setupwizard.h | 12 +-- .../src/plugins/setupwizard/setupwizard.pro | 2 + .../setupwizard/vehicleconfigurationsource.h | 4 +- 7 files changed, 162 insertions(+), 16 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index 3166cd735..f47b98ad4 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -60,14 +60,14 @@ void AirSpeedPage::setupSelection(Selection *selection) selection->addItem(tr("EagleTree"), tr("Select this option to use the Airspeed MicroSensor V3 from EagleTree, this is an accurate " "airspeed sensor that includes on-board Temperature Compensation.\n\n" - "Selecting this option will put your Flexi-Port in to I2C mode."), + "Selecting this option will set your board's Flexi-Port in to I2C mode."), "eagletree", SetupWizard::EAGLETREE); selection->addItem(tr("MS4525 Based"), tr("Select this option to use an airspeed sensor based on the MS4525DO pressure transducer " "from Measurement Specialties. This includes the PixHawk sensor and their clones.\n\n" - "Selecting this option will put your Flexi-Port in to I2C mode."), + "Selecting this option will set your board's Flexi-Port in to I2C mode."), "ms4525", SetupWizard::MS4525); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp new file mode 100644 index 000000000..18531e84e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp @@ -0,0 +1,76 @@ +/** + ****************************************************************************** + * + * @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 "gpspage.h" +#include "setupwizard.h" + +GpsPage::GpsPage(SetupWizard *wizard, QWidget *parent) : + SelectionPage(wizard, QString(":/setupwizard/resources/airspeed-shapes.svg"), parent) +{} + +GpsPage::~GpsPage() +{} + +bool GpsPage::validatePage(SelectionItem *seletedItem) +{ + getWizard()->setGpsType((SetupWizard::GPS_TYPE)seletedItem->id()); + return true; +} + +void GpsPage::setupSelection(Selection *selection) +{ + selection->setTitle(tr("OpenPilot GPS Selection")); + selection->setText(tr("Please select the type of GPS you have below. As well as OpenPilot hardware " + "OpenPilot works hard to support 3rd party GPSs as well, although performance could + "be less than with using OpenPilot produced hardware; not all GPSs are created equal.\n\n" + "Please select your GPS type data below:")); + + selection->addItem(tr("Disabled"), + tr("GPS Features are not to be enabled"), + "disabled", + SetupWizard::GPS_DISABLED); + + selection->addItem(tr("OpenPilot Platinum"), + tr("Select this option to use the OpenPilot Platinum GPS with integrated Magnetometer " + "and Microcontroller connected to the Main Port of your controller.\n\n" + "Note: for the OpenPilot v8 GPS please select the U-Blox option."), + "platinum", + SetupWizard::GPS_PLAT); + + selection->addItem(tr("U-Blox Based"), + tr("Select this option for the OpenPilot V8 GPS or generic U-Blox chipset GPSs connected" + "to the Main Port of your controller."), + "ublox", + SetupWizard::GPS_UBX); + + selection->addItem(tr("NMEA Based"), + tr("Select this option for a generic NMEA based GPS connected to the Main Port of your" + "controller."), + "nmea", + SetupWizard::GPS_NMEA); + +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h new file mode 100644 index 000000000..6ef3512fa --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h @@ -0,0 +1,45 @@ +/** + ****************************************************************************** + * + * @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 GPSPAGE_H +#define GPSPAGE_H + +#include "selectionpage.h" + +class GpsPage : public SelectionPage { + Q_OBJECT + +public: + explicit GpsPage(SetupWizard *wizard, QWidget *parent = 0); + ~GpsPage(); + +public: + bool validatePage(SelectionItem *seletedItem); + void setupSelection(Selection *selection); +}; + +#endif // GPSPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index cfe121966..3716147c4 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -33,6 +33,7 @@ #include "pages/multipage.h" #include "pages/fixedwingpage.h" #include "pages/airspeedpage.h" +#include "pages/gpspage.h" #include "pages/helipage.h" #include "pages/surfacepage.h" #include "pages/inputpage.h" @@ -133,11 +134,23 @@ int SetupWizard::nextId() const if (getVehicleSubType() == MULTI_ROTOR_TRI_Y) { return PAGE_SERVO; } else { - return PAGE_SUMMARY; - } + switch (getControllerType()) { + case CONTROLLER_REVO: + return PAGE_GPS; + default: + return PAGE_SUMMARY; + } + } case PAGE_SERVO: - return PAGE_SUMMARY; + { + switch (getControllerType()) { + case CONTROLLER_REVO: + return PAGE_GPS; + default: + return PAGE_SUMMARY; + } + } case PAGE_BIAS_CALIBRATION: return PAGE_OUTPUT_CALIBRATION; @@ -148,9 +161,9 @@ int SetupWizard::nextId() const { switch (getVehicleType()) { case VEHICLE_FIXEDWING: - return PAGE_AIRSPEED; + return PAGE_AIRFRAMESTAB_FIXEDWING; - // TODO: Pages for Multi and heli + // TODO: PID selection pages for multi and heli case VEHICLE_MULTI: case VEHICLE_HELI: case VEHICLE_SURFACE: @@ -159,8 +172,17 @@ int SetupWizard::nextId() const } } + + case PAGE_GPS: + switch (getVehicleType()) { + case VEHICLE_FIXEDWING: + return PAGE_AIRSPEED; + default: + return PAGE_SUMMARY; + } + case PAGE_AIRSPEED: - return PAGE_AIRFRAMESTAB_FIXEDWING; + return PAGE_SUMMARY; case PAGE_AIRFRAMESTAB_FIXEDWING: return PAGE_SAVE; @@ -364,6 +386,7 @@ void SetupWizard::createPages() setPage(PAGE_MULTI, new MultiPage(this)); setPage(PAGE_FIXEDWING, new FixedWingPage(this)); setPage(PAGE_AIRSPEED, new AirSpeedPage(this)); + setPage(PAGE_GPS, new GpsPage(this)); setPage(PAGE_HELI, new HeliPage(this)); setPage(PAGE_SURFACE, new SurfacePage(this)); setPage(PAGE_INPUT, new InputPage(this)); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h index ef4561567..8fb9fd325 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -106,13 +106,13 @@ public: } - void setGPSSetting(SetupWizard::GPS_SETTING setting) + void setGpsType(SetupWizard::GPS_TYPE setting) { - m_gpsSetting = setting; + m_gpsType = setting; } - SetupWizard::GPS_SETTING getGPSSetting() const + SetupWizard::GPS_TYPE getGpsType() const { - return m_gpsSetting; + return m_gpsType; } void setRadioSetting(SetupWizard::RADIO_SETTING setting) @@ -175,7 +175,7 @@ private slots: void pageChanged(int currId); private: enum { PAGE_START, PAGE_CONTROLLER, PAGE_VEHICLES, PAGE_MULTI, PAGE_FIXEDWING, - PAGE_AIRSPEED, PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_ESC, PAGE_SERVO, + PAGE_AIRSPEED, PAGE_GPS, PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_ESC, PAGE_SERVO, PAGE_BIAS_CALIBRATION, PAGE_REVO_CALIBRATION, PAGE_OUTPUT_CALIBRATION, PAGE_SAVE, PAGE_SUMMARY, PAGE_NOTYETIMPLEMENTED, PAGE_AIRFRAMESTAB_FIXEDWING, PAGE_REBOOT, PAGE_END, PAGE_UPDATE }; @@ -190,7 +190,7 @@ private: ESC_TYPE m_escType; SERVO_TYPE m_servoType; AIRSPEED_TYPE m_airspeedType; - GPS_SETTING m_gpsSetting; + GPS_TYPE m_gpsType; RADIO_SETTING m_radioSetting; bool m_calibrationPerformed; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index ae895118a..eec6f4e69 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -20,6 +20,7 @@ HEADERS += setupwizardplugin.h \ pages/multipage.h \ pages/fixedwingpage.h \ pages/airspeedpage.h \ + pages/gpspage.h \ pages/helipage.h \ pages/surfacepage.h \ pages/abstractwizardpage.h \ @@ -51,6 +52,7 @@ SOURCES += setupwizardplugin.cpp \ pages/multipage.cpp \ pages/fixedwingpage.cpp \ pages/airspeedpage.cpp \ + pages/gpspage.cpp \ pages/helipage.cpp \ pages/surfacepage.cpp \ pages/abstractwizardpage.cpp \ diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 90f70114f..7b7f66b0a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -65,7 +65,7 @@ public: enum SERVO_TYPE { SERVO_ANALOG, SERVO_DIGITAL, SERVO_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN }; enum AIRSPEED_TYPE { ESTIMATE, EAGLETREE, MS4525 }; - enum GPS_SETTING { GPS_PLAT, GPS_UBX, GPS_NMEA, GPS_DISABLED }; + enum GPS_TYPE { GPS_PLAT, GPS_UBX, GPS_NMEA, GPS_DISABLED }; enum RADIO_SETTING { RADIO_TELEMETRY, RADIO_DISABLED }; virtual VehicleConfigurationSource::CONTROLLER_TYPE getControllerType() const = 0; @@ -75,7 +75,7 @@ public: virtual VehicleConfigurationSource::ESC_TYPE getEscType() const = 0; virtual VehicleConfigurationSource::SERVO_TYPE getServoType() const = 0; virtual VehicleConfigurationSource::AIRSPEED_TYPE getAirspeedType() const = 0; - virtual VehicleConfigurationSource::GPS_SETTING getGPSSetting() const = 0; + virtual VehicleConfigurationSource::GPS_TYPE getGpsType() const = 0; virtual VehicleConfigurationSource::RADIO_SETTING getRadioSetting() const = 0; virtual bool isCalibrationPerformed() const = 0; From 14574832b963dc95cc03c1deea28e062e7b9f8fd Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Wed, 3 Sep 2014 07:42:15 +1000 Subject: [PATCH 115/203] Tidy up text --- .../src/plugins/setupwizard/pages/airspeedpage.cpp | 9 ++++----- .../src/plugins/setupwizard/pages/gpspage.cpp | 6 +++--- 2 files changed, 7 insertions(+), 8 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index f47b98ad4..91e259ff1 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -44,16 +44,15 @@ bool AirSpeedPage::validatePage(SelectionItem *seletedItem) void AirSpeedPage::setupSelection(Selection *selection) { selection->setTitle(tr("OpenPilot Airspeed Sensor Selection")); - selection->setText(tr("This part of the wizard will help you select and configure an airspeed sensor which " - "are also commonly called Pitot tubes. OpenPilot support three methods to obtain " - "airspeed data, one is a software estimation technique and the other two " - "utilize hardware sensors.\n\n" + selection->setText(tr("This part of the wizard will help you select and configure a way to obtain " + "airspeed data. OpenPilot support three methods to achieve this, one is a " + "software estimation technique and the other two utilize hardware sensors.\n\n" "Please select how you wish to obtain airspeed data below:")); selection->addItem(tr("Estimated"), tr("This option uses an intelligent estimation algorithm which utilizes the OpenPilot INS/GPS " "to estimate wind speed and subtract it from ground speed obtained from the GPS.\n\n" "This solution is highly accurate in normal level flight with the drawback of being less " - "accurate in rapid altitude changes. "), + "accurate in rapid altitude changes.\n\n"), "estimated", SetupWizard::ESTIMATE); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp index 18531e84e..62caf226c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp @@ -44,9 +44,9 @@ bool GpsPage::validatePage(SelectionItem *seletedItem) void GpsPage::setupSelection(Selection *selection) { selection->setTitle(tr("OpenPilot GPS Selection")); - selection->setText(tr("Please select the type of GPS you have below. As well as OpenPilot hardware " - "OpenPilot works hard to support 3rd party GPSs as well, although performance could - "be less than with using OpenPilot produced hardware; not all GPSs are created equal.\n\n" + selection->setText(tr("Please select the type of GPS you wish to use. As well as OpenPilot hardware, " + "3rd party GPSs are supported also, although please note that performance could " + "be less than optimal as not all GPSs are created equal.\n\n" "Please select your GPS type data below:")); selection->addItem(tr("Disabled"), From a36943c616420196adab8469c61c379b4b1dc0de Mon Sep 17 00:00:00 2001 From: m_thread Date: Wed, 3 Sep 2014 00:05:47 +0200 Subject: [PATCH 116/203] OP-1222 Added svg for gps shapes. Fixed some spelling errors. --- .../setupwizard/pages/airspeedpage.cpp | 4 +- .../plugins/setupwizard/pages/airspeedpage.h | 8 +- .../setupwizard/pages/fixedwingpage.cpp | 4 +- .../plugins/setupwizard/pages/fixedwingpage.h | 2 +- .../src/plugins/setupwizard/pages/gpspage.cpp | 6 +- .../src/plugins/setupwizard/pages/gpspage.h | 8 +- .../setupwizard/resources/gps-shapes.svg | 108 ++++++++++++++++++ .../plugins/setupwizard/wizardResources.qrc | 2 +- 8 files changed, 125 insertions(+), 17 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/gps-shapes.svg diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index 91e259ff1..bd7af6a0c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -35,9 +35,9 @@ AirSpeedPage::AirSpeedPage(SetupWizard *wizard, QWidget *parent) : AirSpeedPage::~AirSpeedPage() {} -bool AirSpeedPage::validatePage(SelectionItem *seletedItem) +bool AirSpeedPage::validatePage(SelectionItem *selectedItem) { - getWizard()->setAirspeedType((SetupWizard::AIRSPEED_TYPE)seletedItem->id()); + getWizard()->setAirspeedType((SetupWizard::AIRSPEED_TYPE)selectedItem->id()); return true; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h index 9b72c967b..6affa4458 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h @@ -1,11 +1,11 @@ /** ****************************************************************************** * - * @file fixedwingpage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @file airspeedpage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. * @addtogroup * @{ - * @addtogroup FixedWingPage + * @addtogroup AirSpeedPage * @{ * @brief *****************************************************************************/ @@ -38,7 +38,7 @@ public: ~AirSpeedPage(); public: - bool validatePage(SelectionItem *seletedItem); + bool validatePage(SelectionItem *selectedItem); void setupSelection(Selection *selection); }; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index 41e7144a8..baa255014 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -35,9 +35,9 @@ FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) : FixedWingPage::~FixedWingPage() {} -bool FixedWingPage::validatePage(SelectionItem *seletedItem) +bool FixedWingPage::validatePage(SelectionItem *selectedItem) { - getWizard()->setVehicleSubType((SetupWizard::VEHICLE_SUB_TYPE)seletedItem->id()); + getWizard()->setVehicleSubType((SetupWizard::VEHICLE_SUB_TYPE)selectedItem->id()); return true; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h index 82c8f21b6..e2e696eeb 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h @@ -38,7 +38,7 @@ public: ~FixedWingPage(); public: - bool validatePage(SelectionItem *seletedItem); + bool validatePage(SelectionItem *selectedItem); void setupSelection(Selection *selection); }; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp index 62caf226c..a7f3499f0 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp @@ -29,15 +29,15 @@ #include "setupwizard.h" GpsPage::GpsPage(SetupWizard *wizard, QWidget *parent) : - SelectionPage(wizard, QString(":/setupwizard/resources/airspeed-shapes.svg"), parent) + SelectionPage(wizard, QString(":/setupwizard/resources/gps-shapes.svg"), parent) {} GpsPage::~GpsPage() {} -bool GpsPage::validatePage(SelectionItem *seletedItem) +bool GpsPage::validatePage(SelectionItem *selectedItem) { - getWizard()->setGpsType((SetupWizard::GPS_TYPE)seletedItem->id()); + getWizard()->setGpsType((SetupWizard::GPS_TYPE)selectedItem->id()); return true; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h index 6ef3512fa..c53df8f17 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h @@ -1,11 +1,11 @@ /** ****************************************************************************** * - * @file fixedwingpage.h - * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @file gpspage.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. * @addtogroup * @{ - * @addtogroup FixedWingPage + * @addtogroup GpsPage * @{ * @brief *****************************************************************************/ @@ -38,7 +38,7 @@ public: ~GpsPage(); public: - bool validatePage(SelectionItem *seletedItem); + bool validatePage(SelectionItem *selectedItem); void setupSelection(Selection *selection); }; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/gps-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/gps-shapes.svg new file mode 100644 index 000000000..350e30e98 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/gps-shapes.svg @@ -0,0 +1,108 @@ + + + + + + + + + + image/svg+xml + + + + + + + OpenPilo + Eagletree + + + MS4525 + + + OpenPilot + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index 8b26ebdcc..725ac2812 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -38,7 +38,6 @@ resources/fixedwing-shapes-wizard.svg resources/fixedwing-shapes-wizard-no-numbers.svg resources/airspeed-shapes.svg - resources/bttn-illustration-down.png resources/bttn-illustration-up.png resources/bttn-save-down.png @@ -47,5 +46,6 @@ resources/bttn-flash-up.png resources/bttn-upgrade-down.png resources/bttn-upgrade-up.png + resources/gps-shapes.svg From fdeb1ccfc9880bb79e5b21f14ca9724733a66958 Mon Sep 17 00:00:00 2001 From: m_thread Date: Wed, 3 Sep 2014 00:31:56 +0200 Subject: [PATCH 117/203] OP-1222 Minor changes in page path code. --- ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 3716147c4..a08c71040 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -135,7 +135,8 @@ int SetupWizard::nextId() const return PAGE_SERVO; } else { switch (getControllerType()) { - case CONTROLLER_REVO: + case CONTROLLER_REVO: + case CONTROLLER_NANO: return PAGE_GPS; default: return PAGE_SUMMARY; @@ -146,6 +147,7 @@ int SetupWizard::nextId() const { switch (getControllerType()) { case CONTROLLER_REVO: + case CONTROLLER_NANO: return PAGE_GPS; default: return PAGE_SUMMARY; From dec4c83b687cb73cf0c71c61e6066dfb44695d4d Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 3 Sep 2014 17:28:38 +0200 Subject: [PATCH 118/203] OP-1222 Artwork for airspeed and gps sensors --- .../setupwizard/resources/sensor-shapes.svg | 4659 +++++++++++++++++ 1 file changed, 4659 insertions(+) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg new file mode 100644 index 000000000..0069aae3b --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg @@ -0,0 +1,4659 @@ + + + + + OpenPilot sensors + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + image/svg+xml + + OpenPilot sensors + + + f5soh + + + + + www.openpilot.org + + + http://www.openpilot.org + 2014 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + MS4525 + MS4525 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + NO GPS + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 60f5fa068a245fd547cb19ef64d9075715af435c Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 3 Sep 2014 21:41:09 +0200 Subject: [PATCH 119/203] OP-1222 connection-diagram.svg file : Added GPS and connectors --- .../resources/connection-diagrams.svg | 8898 ++++++++++++++++- 1 file changed, 8818 insertions(+), 80 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg index 02ee18011..138817d6c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -31,12 +31,12 @@ id="namedview4616" showgrid="false" inkscape:zoom="0.70710678" - inkscape:cx="642.99304" - inkscape:cy="214.47045" + inkscape:cx="652.95764" + inkscape:cy="123.09779" inkscape:window-x="0" inkscape:window-y="27" inkscape:window-maximized="1" - inkscape:current-layer="layer18" + inkscape:current-layer="svg12651" fit-margin-top="15" fit-margin-left="15" fit-margin-right="15" @@ -46,7 +46,8 @@ inkscape:guide-bbox="true" inkscape:snap-global="true" inkscape:snap-bbox="true" - inkscape:object-paths="true"> + inkscape:object-paths="true" + inkscape:snap-bbox-midpoints="true"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -5823,7 +8490,7 @@ image/svg+xml - + @@ -5834,12 +8501,12 @@ style="display:inline" sodipodi:insensitive="true"> @@ -5853,7 +8520,7 @@ inkscape:groupmode="layer" id="layer19" inkscape:label="pwm" - style="display:inline" + style="display:none" sodipodi:insensitive="true"> @@ -6059,7 +8726,7 @@ inkscape:groupmode="layer" id="layer20" inkscape:label="ppm" - style="display:none" + style="display:inline" sodipodi:insensitive="true"> @@ -6140,12 +8807,11 @@ inkscape:groupmode="layer" id="layer21" inkscape:label="sbus" - style="display:none" - sodipodi:insensitive="true"> + style="display:none"> + transform="matrix(0.4,0,0,0.4,-42.525,-134.70912)"> @@ -19894,7 +28622,7 @@ d="m 386.44699,686.89099 c 0,1.51878 -1.23122,2.75 -2.75,2.75 c -1.51878,0 -2.75,-1.23122 -2.75,-2.75 c 0,-1.51878 1.23122,-2.75 2.75,-2.75 c 1.51878,0 2.75,1.23122 2.75,2.75 z" /> @@ -19960,7 +28688,7 @@ d="m 411.435,717.672 c 0,1.51878 -1.23122,2.75 -2.75,2.75 c -1.51879,0 -2.75,-1.23122 -2.75,-2.75 c 0,-1.51879 1.23121,-2.75 2.75,-2.75 c 1.51878,0 2.75,1.23121 2.75,2.75 z" /> @@ -20088,7 +28816,7 @@ d="m 216.804,613.62 c 0,1.51878 -1.23122,2.75 -2.75,2.75 c -1.51878,0 -2.75,-1.23122 -2.75,-2.75 c 0,-1.51879 1.23122,-2.75 2.75,-2.75 c 1.51878,0 2.75,1.23121 2.75,2.75 z" /> @@ -21472,4 +30200,14 @@ + + From b0b475bb602747a7ec9e117f37944f3b00b7128f Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Thu, 4 Sep 2014 00:11:00 +0200 Subject: [PATCH 120/203] OP-1222 Removed "No-sensor", polished estimated airspeed with gears --- .../setupwizard/resources/sensor-shapes.svg | 584 +++++------------- 1 file changed, 141 insertions(+), 443 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg index 0069aae3b..b1ff7d6ea 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg @@ -15,7 +15,7 @@ id="svg2" version="1.1" inkscape:version="0.48.5 r10040" - sodipodi:docname="wizard-sensors.svg" + sodipodi:docname="sensor-shapes.svg" inkscape:export-filename="/home/laurent/Images/sensors_all.png" inkscape:export-xdpi="113.10629" inkscape:export-ydpi="113.10629"> @@ -23,6 +23,42 @@ id="title10373">OpenPilot sensors + + + + + + + + + + + + - - - + + + + + + + + + + + + + + + + + + style="fill:#333333;fill-opacity:1;fill-rule:evenodd;stroke:url(#linearGradient5897);stroke-width:3.05464601999999985;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" + inkscape:export-filename="/home/laurent/Images/Estimated_airspeed.png" + inkscape:export-xdpi="113" + inkscape:export-ydpi="113" /> - - - - + id="g5873" + transform="translate(4,-16.178015)"> + + id="path5783" + style="fill:#1e1b1c;fill-opacity:1;stroke:#1e1b1c;stroke-width:1.10000002;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;filter:url(#filter5845)" + d="m 152.89933,320.55212 c 0.19295,0.0322 0.55726,0.1176 0.80958,0.18997 c 0.25231,0.0724 0.62876,0.15797 0.83655,0.1902 c 0.20779,0.0322 0.47664,0.11643 0.59743,0.1871 c 0.1208,0.0707 0.38306,0.16638 0.58281,0.2127 c 0.19975,0.0463 0.45308,0.14577 0.56296,0.22099 c 0.10988,0.0752 0.32757,0.17425 0.48376,0.22007 c 0.15619,0.0458 0.35049,0.13801 0.43177,0.20487 c 0.0813,0.0668 0.25546,0.16378 0.38706,0.21538 c 0.13159,0.0516 0.31061,0.15388 0.39781,0.22725 c 0.0872,0.0734 0.24669,0.17023 0.35442,0.21523 c 0.10774,0.045 0.2566,0.13849 0.33081,0.20773 c 0.0742,0.0693 0.20979,0.16362 0.30129,0.20973 c 0.17591,0.0886 0.48886,0.32602 0.87922,0.6669 c 0.30005,0.26203 1.6381,1.60115 1.92286,1.92442 c 0.42143,0.47841 1.02232,1.30566 1.07724,1.48304 c 0.0213,0.0688 0.10767,0.20354 0.19198,0.29955 c 0.0843,0.096 0.19566,0.28265 0.24746,0.41473 c 0.0518,0.13209 0.14849,0.30621 0.21487,0.38692 c 0.0663,0.0807 0.16236,0.275 0.21332,0.43177 c 0.051,0.15676 0.14899,0.36063 0.21788,0.45304 c 0.0689,0.0924 0.16391,0.33473 0.21117,0.53851 c 0.0472,0.20377 0.14787,0.47619 0.22357,0.60537 c 0.0831,0.14183 0.16632,0.40956 0.21004,0.67585 c 0.0398,0.24254 0.13225,0.59884 0.20542,0.79179 c 0.0838,0.2209 0.15501,0.57067 0.19241,0.9445 c 0.1012,1.01138 0.16848,2.29223 0.14003,2.66571 c -0.0149,0.19619 -0.0523,0.72101 -0.083,1.16627 c -0.0706,1.02353 -0.13055,1.40617 -0.2695,1.72029 c -0.0609,0.13761 -0.14426,0.45763 -0.1853,0.71114 c -0.0465,0.28741 -0.12664,0.54972 -0.21283,0.69678 c -0.076,0.12971 -0.16463,0.36541 -0.19693,0.52378 c -0.0323,0.15837 -0.12924,0.40428 -0.21542,0.54649 c -0.0862,0.1422 -0.19467,0.3891 -0.24106,0.54868 c -0.0464,0.15958 -0.12365,0.32254 -0.1717,0.36213 c -0.048,0.0396 -0.16774,0.24807 -0.26598,0.46328 c -0.0982,0.21521 -0.20069,0.39129 -0.22764,0.39129 c -0.027,0 -0.11289,0.12751 -0.19095,0.28336 c -0.13427,0.26803 -0.32164,0.53648 -0.66438,0.95189 c -0.083,0.10053 -0.1767,0.22941 -0.20833,0.28639 c -0.18097,0.32607 -2.06494,2.20815 -2.39291,2.39053 c -0.0542,0.0301 -0.18072,0.12283 -0.28126,0.20606 c -0.35107,0.29059 -0.77794,0.58447 -0.96465,0.66411 c -0.10348,0.0441 -0.23731,0.12643 -0.29738,0.18287 c -0.06,0.0564 -0.2547,0.1666 -0.43251,0.24479 c -0.17781,0.0782 -0.37186,0.18647 -0.43123,0.24057 c -0.0593,0.0541 -0.24048,0.13728 -0.40248,0.18482 c -0.162,0.0475 -0.38058,0.14597 -0.48574,0.21873 c -0.10516,0.0728 -0.35954,0.17128 -0.56527,0.21892 c -0.20573,0.0477 -0.47289,0.14421 -0.59369,0.21462 c -0.12732,0.0742 -0.42378,0.16322 -0.70537,0.21178 c -0.26716,0.046 -0.62485,0.13265 -0.79487,0.19242 c -0.48377,0.17005 -0.93335,0.21562 -2.47041,0.25042 c -1.76934,0.0401 -2.81102,-0.0267 -3.45418,-0.22139 c -0.25232,-0.0764 -0.67734,-0.17619 -0.9445,-0.22183 c -0.28967,-0.0495 -0.57663,-0.13603 -0.71089,-0.21443 c -0.12384,-0.0723 -0.391,-0.16949 -0.59369,-0.21597 c -0.2027,-0.0465 -0.45725,-0.14539 -0.56569,-0.2198 c -0.10842,-0.0744 -0.31487,-0.17053 -0.45875,-0.21362 c -0.14389,-0.0431 -0.35877,-0.14726 -0.47751,-0.2315 c -0.11874,-0.0842 -0.30501,-0.18214 -0.41396,-0.21756 c -0.10894,-0.0354 -0.22893,-0.10157 -0.26663,-0.147 c -0.0377,-0.0455 -0.20358,-0.15104 -0.36862,-0.2347 c -0.16504,-0.0837 -0.35895,-0.21526 -0.43092,-0.29244 c -0.072,-0.0772 -0.15867,-0.14034 -0.19268,-0.14034 c -0.034,0 -0.15728,-0.0801 -0.27394,-0.17796 c -0.11666,-0.0979 -0.28876,-0.22539 -0.38244,-0.28335 c -0.50014,-0.30945 -2.28751,-2.10121 -2.50097,-2.50712 c -0.039,-0.0742 -0.16435,-0.24157 -0.2785,-0.37191 c -0.11414,-0.13034 -0.20754,-0.26575 -0.20754,-0.30093 c 0,-0.0352 -0.0588,-0.11921 -0.13071,-0.18675 c -0.0719,-0.0675 -0.20225,-0.27257 -0.28969,-0.45562 c -0.0874,-0.18306 -0.1974,-0.36471 -0.24433,-0.40366 c -0.047,-0.0389 -0.11471,-0.15996 -0.15061,-0.26891 c -0.0359,-0.10894 -0.14642,-0.31617 -0.24563,-0.46049 c -0.0992,-0.14434 -0.18037,-0.30651 -0.18037,-0.36039 c 0,-0.0539 -0.0855,-0.26198 -0.18999,-0.46245 c -0.10449,-0.20047 -0.2269,-0.52369 -0.27203,-0.71827 c -0.0451,-0.19458 -0.1325,-0.43914 -0.19418,-0.54346 c -0.0617,-0.10432 -0.15736,-0.44009 -0.21265,-0.74613 c -0.0553,-0.30605 -0.16262,-0.77965 -0.23854,-1.05245 c -0.29139,-1.0471 -0.29504,-4.00998 -0.006,-5.11056 c 0.074,-0.282 0.17446,-0.74346 0.2233,-1.02546 c 0.0489,-0.282 0.15726,-0.6706 0.24094,-0.86355 c 0.0837,-0.19294 0.17756,-0.47225 0.20863,-0.62067 c 0.0311,-0.14842 0.14295,-0.43556 0.24865,-0.63809 c 0.10569,-0.20252 0.19217,-0.4117 0.19217,-0.46483 c 0,-0.0531 0.0714,-0.18646 0.1587,-0.29629 c 0.0873,-0.10983 0.1979,-0.31774 0.24582,-0.46202 c 0.0479,-0.14429 0.12496,-0.29372 0.17118,-0.33209 c 0.0462,-0.0384 0.15443,-0.21503 0.24044,-0.39258 c 0.086,-0.17756 0.1817,-0.33848 0.21265,-0.35761 c 0.0552,-0.0341 0.22638,-0.26991 0.62538,-0.86148 c 0.11011,-0.16327 0.26265,-0.3609 0.33895,-0.4392 c 0.0763,-0.0783 0.24804,-0.26568 0.38162,-0.41641 c 0.59163,-0.66759 1.53208,-1.56152 1.84734,-1.75593 c 0.0971,-0.0599 0.27205,-0.189 0.38871,-0.28688 c 0.11666,-0.0979 0.23994,-0.17797 0.27394,-0.17797 c 0.034,0 0.12072,-0.0637 0.19268,-0.14143 c 0.072,-0.0778 0.23482,-0.18654 0.36189,-0.24166 c 0.12708,-0.0552 0.32137,-0.17064 0.43178,-0.25668 c 0.11039,-0.0861 0.28356,-0.18385 0.38482,-0.21732 c 0.10125,-0.0335 0.25912,-0.11775 0.35081,-0.18728 c 0.0917,-0.0695 0.28882,-0.16673 0.43805,-0.21601 c 0.14923,-0.0493 0.3586,-0.1489 0.46527,-0.22138 c 0.10667,-0.0725 0.35685,-0.16957 0.55597,-0.21575 c 0.19911,-0.0462 0.46406,-0.14375 0.58876,-0.21684 c 0.14498,-0.085 0.41108,-0.16235 0.73789,-0.21461 c 0.28112,-0.045 0.71758,-0.1448 0.96989,-0.22186 c 0.28289,-0.0864 0.68635,-0.1577 1.05245,-0.18595 c 0.77071,-0.0595 3.62171,-0.0223 4.07485,0.0531 z m -4.95328,-24.23083 c -0.0713,0.0291 -0.16776,0.15493 -0.22986,0.29979 c -0.0588,0.13732 -0.15416,0.30961 -0.21178,0.38285 c -0.0576,0.0732 -0.14425,0.26908 -0.19255,0.43519 c -0.0483,0.16613 -0.147,0.37966 -0.21935,0.47452 c -0.0724,0.0948 -0.1717,0.29117 -0.22077,0.43625 c -0.0491,0.14508 -0.14755,0.3525 -0.21885,0.46093 c -0.0713,0.10844 -0.16494,0.31453 -0.20811,0.45799 c -0.0432,0.14346 -0.13667,0.34874 -0.20777,0.45617 c -0.0711,0.10743 -0.16652,0.32077 -0.21204,0.47408 c -0.0455,0.1533 -0.1552,0.38148 -0.24372,0.50707 c -0.0885,0.12557 -0.18631,0.3261 -0.21731,0.44562 c -0.031,0.11952 -0.11704,0.29954 -0.19118,0.40003 c -0.0741,0.10051 -0.1733,0.31513 -0.22035,0.47696 c -0.047,0.16183 -0.14644,0.38627 -0.22088,0.49876 c -0.0744,0.11249 -0.17059,0.32163 -0.21367,0.46476 c -0.0431,0.14314 -0.13707,0.34587 -0.20888,0.45051 c -0.0718,0.10464 -0.18087,0.32591 -0.24236,0.4917 c -0.12768,0.34431 -0.26391,0.49221 -0.57018,0.61909 c -0.11833,0.049 -0.318,0.13562 -0.44371,0.19245 c -0.1257,0.0569 -0.42171,0.13997 -0.65777,0.18475 c -0.23607,0.0448 -0.55824,0.1399 -0.71595,0.21139 c -0.15769,0.0715 -0.49316,0.16861 -0.74548,0.21585 c -0.25232,0.0472 -0.57473,0.14653 -0.71646,0.22063 c -0.14173,0.0741 -0.36141,0.14895 -0.48817,0.16632 c -0.19617,0.0269 -0.25556,0.0105 -0.39888,-0.1101 c -0.0926,-0.0779 -0.29796,-0.19915 -0.45633,-0.26938 c -0.15836,-0.0702 -0.33601,-0.18109 -0.39477,-0.24637 c -0.0588,-0.0653 -0.18845,-0.15281 -0.28818,-0.19447 c -0.0997,-0.0416 -0.25495,-0.13772 -0.34493,-0.21343 c -0.09,-0.0757 -0.25175,-0.17449 -0.35948,-0.21949 c -0.10774,-0.045 -0.2566,-0.13858 -0.33081,-0.20795 c -0.0742,-0.0694 -0.23491,-0.17622 -0.3571,-0.23744 c -0.1222,-0.0612 -0.29221,-0.16985 -0.37781,-0.24141 c -0.0856,-0.0716 -0.21187,-0.14774 -0.2806,-0.16926 c -0.0688,-0.0215 -0.20562,-0.10993 -0.30418,-0.19647 c -0.0985,-0.0865 -0.27304,-0.196 -0.38774,-0.24329 c -0.11472,-0.0472 -0.26408,-0.13724 -0.33192,-0.19993 c -0.11835,-0.10934 -0.25247,-0.19357 -0.87639,-0.55031 c -0.15575,-0.089 -0.36212,-0.22879 -0.45862,-0.31051 c -0.0965,-0.0817 -0.26929,-0.18721 -0.384,-0.2344 c -0.11471,-0.0472 -0.26927,-0.14297 -0.34348,-0.21285 c -0.0742,-0.0699 -0.22019,-0.16266 -0.32439,-0.20619 c -0.10421,-0.0435 -0.2563,-0.14108 -0.33798,-0.21678 c -0.17706,-0.16409 -0.51803,-0.27652 -0.70006,-0.23083 c -0.072,0.0181 -0.22597,0.10845 -0.34222,0.20086 c -0.11623,0.0924 -0.29635,0.20353 -0.40025,0.24695 c -0.10389,0.0434 -0.24962,0.1356 -0.32383,0.20485 c -0.0742,0.0693 -0.21574,0.1667 -0.31451,0.21657 c -0.0988,0.0498 -0.28886,0.17408 -0.42242,0.27602 c -0.13355,0.10195 -0.27362,0.18535 -0.31128,0.18535 c -0.0377,0 -0.11472,0.0513 -0.17127,0.11384 c -0.0566,0.0626 -0.2364,0.1814 -0.39966,0.26396 c -0.16326,0.0826 -0.3411,0.19913 -0.39519,0.25903 c -0.0541,0.0599 -0.17554,0.13986 -0.26986,0.17768 c -0.0943,0.0378 -0.24176,0.1264 -0.32763,0.19683 c -0.0859,0.0704 -0.27313,0.18734 -0.41615,0.25982 c -0.35143,0.17808 -0.40066,0.35709 -0.32003,1.16362 c 0.0585,0.58488 0.0849,0.74787 0.24004,1.47816 c 0.0441,0.20779 0.11814,0.81497 0.16445,1.34929 c 0.0463,0.53432 0.14435,1.26423 0.21786,1.62202 c 0.0735,0.35779 0.16959,1.07426 0.21352,1.59216 c 0.0439,0.51789 0.12693,1.17033 0.18444,1.44986 c 0.0575,0.27951 0.0899,0.54667 0.0719,0.59369 c -0.0389,0.10165 -0.34625,0.5102 -0.52945,0.7037 c -0.40067,0.42318 -1.66996,1.88634 -1.95863,2.25778 c -0.0989,0.12729 -0.27326,0.27908 -0.38744,0.33732 c -0.20114,0.10263 -0.3419,0.10591 -4.53517,0.10591 l -4.32759,0 l -0.25508,0.25636 c -0.19362,0.1946 -0.27728,0.33328 -0.34719,0.57559 c -0.0506,0.17557 -0.15174,0.4063 -0.22462,0.51273 c -0.0729,0.10643 -0.16876,0.31709 -0.21309,0.46812 c -0.0443,0.15104 -0.14013,0.35534 -0.21293,0.454 c -0.0728,0.0987 -0.17084,0.3118 -0.21788,0.47363 c -0.047,0.16183 -0.14644,0.38626 -0.22088,0.49876 c -0.0744,0.11248 -0.17067,0.32189 -0.21385,0.46535 c -0.0432,0.14346 -0.13998,0.35374 -0.21514,0.4673 c -0.16566,0.25034 -0.31966,0.84041 -0.27049,1.03637 c 0.0197,0.0784 0.11382,0.22367 0.20921,0.32285 c 0.0954,0.0992 0.29487,0.33082 0.44329,0.51473 c 0.30751,0.38104 0.70356,0.85195 0.95905,1.14033 c 0.0959,0.10823 0.27151,0.30857 0.39024,0.4452 c 0.11874,0.13662 0.30089,0.342 0.40479,0.45639 c 0.10389,0.11439 0.31034,0.36122 0.45876,0.5485 c 0.29365,0.37053 0.98465,1.19312 1.29148,1.53743 c 0.19594,0.21987 0.28516,0.32194 1.04919,1.20026 c 0.28363,0.32607 0.4453,0.56025 0.46715,0.67669 c 0.0462,0.24624 -0.069,1.43256 -0.1898,1.95503 c -0.10576,0.45735 -0.18513,0.98942 -0.2647,1.77434 c -0.0557,0.549 -0.13168,0.68617 -0.50038,0.9028 c -0.13268,0.078 -0.30525,0.20575 -0.38349,0.28399 c -0.0782,0.0782 -0.17792,0.14224 -0.22152,0.14224 c -0.0436,0 -0.18912,0.0838 -0.32336,0.18631 c -0.13425,0.10247 -0.3381,0.23428 -0.45301,0.2929 c -0.11491,0.0586 -0.24211,0.14657 -0.28266,0.19543 c -0.0406,0.0489 -0.16776,0.13682 -0.28267,0.19544 c -0.11491,0.0586 -0.31876,0.19042 -0.45301,0.29289 c -0.13424,0.10248 -0.27441,0.18632 -0.3115,0.18632 c -0.0371,0 -0.12629,0.064 -0.19826,0.14226 c -0.072,0.0782 -0.23298,0.1882 -0.35782,0.24434 c -0.12483,0.0562 -0.29484,0.15881 -0.3778,0.22816 c -0.0829,0.0693 -0.2496,0.17621 -0.37032,0.23747 c -0.12072,0.0613 -0.25268,0.15135 -0.29323,0.20022 c -0.0406,0.0489 -0.17251,0.13831 -0.29323,0.19878 c -0.12073,0.0605 -0.28022,0.16669 -0.35443,0.23606 c -0.0742,0.0694 -0.22042,0.16185 -0.32493,0.2055 c -0.10449,0.0436 -0.23807,0.13278 -0.29684,0.19806 c -0.0588,0.0653 -0.22828,0.17266 -0.37671,0.2386 c -0.14842,0.0659 -0.30476,0.16216 -0.34742,0.21379 c -0.0426,0.0516 -0.19027,0.15101 -0.32801,0.22081 c -0.25103,0.12721 -0.49179,0.38534 -0.55964,0.60002 c -0.0201,0.0636 0.0375,0.46051 0.12923,0.89053 c 0.091,0.42672 0.20183,1.17659 0.24628,1.66639 c 0.0445,0.48979 0.11783,1.03625 0.16308,1.21436 c 0.0453,0.1781 0.1285,0.57884 0.18501,0.89053 c 0.12185,0.67202 0.15705,0.71244 0.6985,0.80187 c 0.21199,0.035 0.49951,0.12329 0.63892,0.19617 c 0.13942,0.0729 0.4581,0.17134 0.70818,0.21877 c 0.25008,0.0474 0.56582,0.14246 0.70163,0.21117 c 0.13582,0.0687 0.45338,0.16616 0.7057,0.21655 c 0.25232,0.0504 0.5879,0.1518 0.74572,0.22532 c 0.15783,0.0735 0.46939,0.16858 0.69236,0.21125 c 0.22296,0.0426 0.56742,0.14773 0.76548,0.2335 c 0.19804,0.0858 0.5274,0.18426 0.73188,0.21887 c 0.20448,0.0346 0.48985,0.12276 0.63416,0.19588 c 0.14431,0.0731 0.44967,0.1688 0.67859,0.21259 c 0.64254,0.12294 0.74433,0.17198 1.05625,0.50889 c 0.22378,0.24171 0.31131,0.38751 0.38035,0.63359 c 0.0494,0.17579 0.14993,0.40128 0.22357,0.50109 c 0.0736,0.0998 0.17237,0.31387 0.21941,0.47569 c 0.047,0.16183 0.14421,0.3829 0.21593,0.49128 c 0.0717,0.10837 0.16514,0.3125 0.20762,0.45364 c 0.0425,0.14113 0.15839,0.38306 0.25761,0.53763 c 0.1688,0.26298 0.18039,0.31088 0.18039,0.74563 c 0,0.42917 -0.0132,0.48589 -0.17344,0.74384 c -0.0954,0.15359 -0.21095,0.40553 -0.25679,0.55987 c -0.0458,0.15434 -0.14538,0.37016 -0.22122,0.4796 c -0.0758,0.10944 -0.17129,0.32557 -0.21211,0.48031 c -0.0408,0.15472 -0.1331,0.37031 -0.20507,0.47907 c -0.072,0.10876 -0.17213,0.33967 -0.22255,0.51311 c -0.0504,0.17344 -0.15258,0.40739 -0.22702,0.51988 c -0.0744,0.11248 -0.17067,0.32189 -0.21384,0.46535 c -0.0432,0.14346 -0.13718,0.3495 -0.2089,0.45787 c -0.0717,0.10837 -0.16888,0.32944 -0.21592,0.49127 c -0.047,0.16183 -0.1451,0.37496 -0.21789,0.47362 c -0.0728,0.0987 -0.17084,0.3118 -0.21789,0.47363 c -0.047,0.16182 -0.14644,0.38626 -0.22088,0.49875 c -0.0744,0.11249 -0.17067,0.32189 -0.21384,0.46535 c -0.0432,0.14346 -0.1394,0.35286 -0.21383,0.46534 c -0.14614,0.22082 -0.25807,0.68182 -0.20287,0.83547 c 0.0188,0.0523 0.10917,0.17064 0.2009,0.26313 c 0.0917,0.0925 0.25646,0.27464 0.36607,0.40479 c 0.10961,0.13014 0.3282,0.39002 0.48575,0.57751 c 0.95192,1.13279 1.72021,2.00509 2.2073,2.50612 c 0.3581,0.36835 0.45884,0.3845 0.94972,0.15228 c 0.18365,-0.0869 0.54796,-0.19765 0.80957,-0.24615 c 0.26161,-0.0485 0.60502,-0.14692 0.76313,-0.21869 c 0.1581,-0.0718 0.49403,-0.16656 0.74652,-0.21063 c 0.25249,-0.044 0.59156,-0.14078 0.75349,-0.21492 c 0.16194,-0.0741 0.38461,-0.14933 0.49482,-0.1671 c 0.44349,-0.0715 0.75552,-0.15395 1.05865,-0.27972 c 0.1752,-0.0727 0.525,-0.16819 0.77732,-0.21224 c 0.25233,-0.044 0.57142,-0.13716 0.7091,-0.20692 c 0.13768,-0.0697 0.46967,-0.1647 0.73777,-0.21097 c 0.2681,-0.0462 0.595,-0.13291 0.72644,-0.19254 c 0.32043,-0.14536 0.51399,-0.13876 0.70759,0.0241 c 0.0882,0.0742 0.19306,0.13493 0.23303,0.13493 c 0.04,0 0.18789,0.0879 0.3287,0.19541 c 0.1408,0.10749 0.33138,0.22691 0.4235,0.2654 c 0.0921,0.0385 0.21559,0.12409 0.27435,0.19023 c 0.0588,0.0661 0.20899,0.16594 0.33383,0.2218 c 0.12483,0.0559 0.29485,0.15822 0.3778,0.22744 c 0.083,0.0693 0.23583,0.1685 0.33972,0.22059 c 0.1039,0.0521 0.24962,0.15034 0.32383,0.21833 c 0.0742,0.068 0.24983,0.17698 0.39027,0.24218 c 0.31371,0.14564 0.4447,0.34704 0.52639,0.80925 c 0.0341,0.19295 0.10727,0.53297 0.16262,0.75561 c 0.0553,0.22263 0.13994,0.81024 0.188,1.3058 c 0.0481,0.49557 0.14495,1.13918 0.21531,1.43025 c 0.0704,0.29107 0.16736,0.92997 0.21557,1.41976 c 0.0482,0.48979 0.14797,1.14192 0.2217,1.44917 c 0.0737,0.30725 0.15898,0.81728 0.18946,1.1334 c 0.0922,0.95582 0.14224,1.03642 0.72641,1.16916 c 0.20657,0.047 0.54559,0.15454 0.75338,0.23912 c 0.20779,0.0846 0.51139,0.17094 0.67465,0.19192 c 0.16326,0.021 0.45471,0.10663 0.64766,0.19035 c 0.19295,0.0837 0.5684,0.19294 0.83435,0.2427 c 0.26594,0.0498 0.60077,0.15177 0.74408,0.2267 c 0.14534,0.076 0.43898,0.16194 0.66408,0.19437 l 0.40353,0.0581 l 0.32594,-0.34818 c 0.17926,-0.19148 0.41773,-0.44532 0.52992,-0.56405 c 0.29977,-0.31725 1.78308,-2.01041 2.01484,-2.29987 c 0.10963,-0.13693 0.32793,-0.38585 0.48514,-0.55317 c 0.15719,-0.16732 0.38296,-0.41782 0.50169,-0.55667 c 0.22778,-0.26634 0.50606,-0.57604 0.86355,-0.96103 c 0.11873,-0.12787 0.31304,-0.34714 0.43177,-0.48727 c 0.53074,-0.62635 0.86426,-0.93285 1.07943,-0.99197 c 0.13805,-0.038 0.90935,-0.0594 2.13917,-0.0596 l 1.92328,-2.1e-4 l 0.28955,0.24164 c 0.15926,0.13291 0.411,0.39003 0.55942,0.57138 c 0.37333,0.45617 1.51356,1.76528 2.01381,2.31208 c 0.2282,0.24944 0.49467,0.54088 0.59215,0.64766 c 0.36141,0.39586 1.44869,1.65768 1.58574,1.84028 c 0.078,0.10389 0.2961,0.35176 0.48472,0.5508 c 0.18861,0.19904 0.38264,0.41763 0.43117,0.48574 c 0.13309,0.18683 0.70197,0.1699 1.1801,-0.0351 c 0.19295,-0.0827 0.54511,-0.19194 0.78258,-0.24269 c 0.23748,-0.0508 0.59838,-0.15906 0.80201,-0.24069 c 0.20363,-0.0816 0.56793,-0.18569 0.80957,-0.23125 c 0.24163,-0.0455 0.55284,-0.14033 0.69155,-0.2106 c 0.13872,-0.0702 0.42623,-0.15651 0.63892,-0.19164 c 0.2127,-0.0351 0.43405,-0.10245 0.49188,-0.14961 c 0.0761,-0.062 0.13354,-0.24233 0.2079,-0.65246 c 0.0565,-0.31169 0.13989,-0.71243 0.18528,-0.89054 c 0.0454,-0.1781 0.1217,-0.72456 0.16955,-1.21436 c 0.0479,-0.48979 0.14512,-1.1334 0.21612,-1.43024 c 0.071,-0.29685 0.16654,-0.92831 0.21232,-1.40326 c 0.0458,-0.47495 0.14263,-1.11856 0.21523,-1.43025 c 0.0726,-0.31168 0.15839,-0.83128 0.19067,-1.15465 c 0.0764,-0.76554 0.18401,-0.9639 0.64712,-1.19296 c 0.10389,-0.0514 0.24962,-0.15009 0.32383,-0.21934 c 0.0742,-0.0693 0.2251,-0.16357 0.33531,-0.2096 c 0.11021,-0.046 0.28022,-0.15335 0.3778,-0.23846 c 0.0976,-0.0851 0.23366,-0.17231 0.3024,-0.19378 c 0.0688,-0.0215 0.20561,-0.10983 0.30418,-0.19636 c 0.0985,-0.0865 0.26485,-0.19313 0.36956,-0.23687 c 0.10472,-0.0438 0.27077,-0.15297 0.36902,-0.2427 c 0.0982,-0.0897 0.2063,-0.16315 0.24013,-0.16315 c 0.0339,0 0.15319,-0.0729 0.26525,-0.16191 c 0.2414,-0.19185 0.40583,-0.20247 0.78997,-0.0511 c 0.15468,0.061 0.47739,0.14784 0.71712,0.19304 c 0.23974,0.0452 0.60589,0.14928 0.81368,0.23128 c 0.20779,0.082 0.55008,0.17688 0.76064,0.21085 c 0.21056,0.034 0.51585,0.12267 0.67843,0.19709 c 0.16257,0.0744 0.48894,0.16909 0.72527,0.21034 c 0.23634,0.0413 0.59131,0.13967 0.78882,0.21869 c 0.19753,0.079 0.56108,0.18152 0.80788,0.22777 c 0.24681,0.0462 0.57221,0.14221 0.7231,0.21323 c 0.1509,0.071 0.48912,0.1666 0.75162,0.21238 c 0.26249,0.0457 0.58835,0.13896 0.72411,0.20709 c 0.6482,0.32523 0.76557,0.2776 1.48821,-0.60393 c 0.0593,-0.0724 0.19691,-0.23171 0.30565,-0.35396 c 0.10875,-0.12226 0.32733,-0.36988 0.48575,-0.55028 c 0.15841,-0.18039 0.35419,-0.39898 0.43503,-0.48574 c 0.13666,-0.14664 0.5904,-0.67483 1.26975,-1.47809 c 0.2314,-0.27358 0.28336,-0.37197 0.28336,-0.53651 c 0,-0.27238 -0.14238,-0.73357 -0.30002,-0.97177 c -0.0711,-0.10744 -0.16459,-0.31271 -0.20776,-0.45617 c -0.0432,-0.14346 -0.13941,-0.35286 -0.21385,-0.46535 c -0.0744,-0.11249 -0.17383,-0.33693 -0.22088,-0.49875 c -0.047,-0.16183 -0.14509,-0.37496 -0.21788,-0.47363 c -0.0728,-0.0987 -0.16861,-0.30296 -0.21293,-0.454 c -0.0443,-0.15104 -0.1397,-0.36095 -0.21195,-0.46646 c -0.0723,-0.10551 -0.16762,-0.31391 -0.21192,-0.46309 c -0.0443,-0.1492 -0.15421,-0.40289 -0.24423,-0.56376 c -0.09,-0.16088 -0.18013,-0.38288 -0.20025,-0.49334 c -0.0201,-0.11047 -0.10606,-0.31042 -0.19098,-0.44434 c -0.0849,-0.13393 -0.19224,-0.37356 -0.23846,-0.53254 c -0.0462,-0.15896 -0.14358,-0.36975 -0.21637,-0.46842 c -0.0728,-0.0987 -0.16885,-0.30297 -0.21347,-0.454 c -0.0446,-0.15104 -0.15438,-0.38391 -0.24392,-0.51749 c -0.22716,-0.33885 -0.22798,-0.69786 -0.002,-1.03083 c 0.0885,-0.13062 0.19965,-0.36901 0.24696,-0.52973 c 0.0473,-0.16073 0.14565,-0.37932 0.21853,-0.48575 c 0.0729,-0.10643 0.16877,-0.31708 0.21309,-0.46812 c 0.0443,-0.15104 0.14013,-0.35534 0.21293,-0.454 c 0.0728,-0.0987 0.16975,-0.30806 0.21547,-0.46532 c 0.0457,-0.15726 0.15993,-0.41442 0.25381,-0.57145 c 0.0939,-0.15705 0.19972,-0.33466 0.2352,-0.3947 c 0.10533,-0.17823 0.57506,-0.39772 1.0399,-0.48589 c 0.23909,-0.0453 0.56507,-0.14215 0.72439,-0.21509 c 0.15933,-0.0729 0.49297,-0.17119 0.74142,-0.21832 c 0.24846,-0.0472 0.56469,-0.14293 0.70275,-0.21289 c 0.13805,-0.07 0.44922,-0.16479 0.69151,-0.21075 c 0.24226,-0.046 0.558,-0.14311 0.70162,-0.21588 c 0.14362,-0.0728 0.46575,-0.17114 0.71583,-0.21857 c 0.25008,-0.0474 0.56498,-0.1439 0.69977,-0.21438 c 0.1348,-0.0704 0.46033,-0.16846 0.72343,-0.21776 c 0.26308,-0.0493 0.5913,-0.14688 0.72938,-0.21685 c 0.13808,-0.07 0.34686,-0.14364 0.46395,-0.16373 c 0.55814,-0.0957 0.61076,-0.12415 0.75448,-0.40776 c 0.17117,-0.33777 0.22334,-0.61301 0.32377,-1.70817 c 0.0441,-0.48141 0.13942,-1.14931 0.21172,-1.48422 c 0.15014,-0.69553 0.2733,-1.75816 0.22573,-1.94769 c -0.0519,-0.20669 -0.24292,-0.40975 -0.51542,-0.54783 c -0.13994,-0.0709 -0.28772,-0.16904 -0.32839,-0.21805 c -0.0406,-0.049 -0.16798,-0.13707 -0.28289,-0.19569 c -0.11491,-0.0586 -0.31877,-0.19044 -0.45301,-0.29291 c -0.13424,-0.10247 -0.27859,-0.1863 -0.32078,-0.1863 c -0.0422,0 -0.16682,-0.085 -0.27697,-0.18891 c -0.11014,-0.10389 -0.22977,-0.1889 -0.26585,-0.1889 c -0.036,0 -0.17541,-0.0838 -0.30966,-0.18631 c -0.13424,-0.10247 -0.3381,-0.23427 -0.453,-0.2929 c -0.11492,-0.0586 -0.24211,-0.14657 -0.28267,-0.19543 c -0.0406,-0.0489 -0.16775,-0.13681 -0.28267,-0.19544 c -0.11491,-0.0586 -0.31876,-0.19042 -0.45301,-0.2929 c -0.13424,-0.10247 -0.27442,-0.18631 -0.31149,-0.18631 c -0.0371,0 -0.1263,-0.064 -0.19826,-0.14225 c -0.072,-0.0783 -0.23299,-0.1882 -0.35782,-0.24434 c -0.12484,-0.0562 -0.29485,-0.15882 -0.3778,-0.22816 c -0.083,-0.0693 -0.2496,-0.17621 -0.37032,-0.23747 c -0.12073,-0.0613 -0.25278,-0.15148 -0.29346,-0.20049 c -0.0406,-0.049 -0.18477,-0.14531 -0.32022,-0.21399 c -0.13544,-0.0687 -0.28948,-0.17272 -0.34231,-0.23119 c -0.0528,-0.0585 -0.19444,-0.15067 -0.31469,-0.2049 c -0.17249,-0.0778 -0.25044,-0.16194 -0.36936,-0.39877 c -0.15975,-0.31814 -0.22738,-0.70341 -0.32746,-1.86535 c -0.0307,-0.35621 -0.11888,-0.91262 -0.196,-1.23646 c -0.19827,-0.83258 -0.19666,-1.09566 0.008,-1.33979 c 0.089,-0.1061 0.28335,-0.3433 0.43177,-0.52712 c 0.29617,-0.36679 0.63584,-0.77268 0.9259,-1.10641 c 0.10319,-0.11874 0.2771,-0.31906 0.38647,-0.44514 c 0.10936,-0.1261 0.29598,-0.33627 0.41472,-0.46704 c 0.11874,-0.13077 0.33733,-0.38903 0.48575,-0.5739 c 0.43309,-0.53944 1.03399,-1.24997 1.64165,-1.94112 c 0.76287,-0.8677 1.07659,-1.23596 1.18603,-1.39218 c 0.14323,-0.20448 0.16012,-0.46572 0.0447,-0.69146 c -0.0439,-0.0859 -0.0963,-0.2325 -0.11635,-0.32577 c -0.02,-0.0933 -0.10721,-0.28107 -0.19362,-0.41734 c -0.0864,-0.13627 -0.19494,-0.37783 -0.24116,-0.5368 c -0.0462,-0.15897 -0.14358,-0.36976 -0.21637,-0.46843 c -0.0728,-0.0987 -0.17085,-0.31179 -0.21789,-0.47362 c -0.047,-0.16183 -0.14421,-0.3829 -0.21592,-0.49127 c -0.0717,-0.10837 -0.16572,-0.31441 -0.2089,-0.45787 c -0.0432,-0.14346 -0.13709,-0.34955 -0.2087,-0.45799 c -0.0716,-0.10843 -0.16099,-0.2943 -0.19862,-0.41304 c -0.0973,-0.30712 -0.1942,-0.44278 -0.39422,-0.55208 c -0.16209,-0.0886 -0.49628,-0.0976 -4.56311,-0.12256 l -4.3882,-0.027 l -0.32206,-0.35082 c -0.17713,-0.19295 -0.42471,-0.46634 -0.55019,-0.60755 c -0.49188,-0.55353 -0.61317,-0.69096 -0.80707,-0.91457 c -0.11063,-0.12758 -0.28588,-0.3291 -0.38946,-0.44784 c -0.56548,-0.64823 -0.73775,-0.86881 -0.76578,-0.98046 c -0.0429,-0.17107 0.12913,-2.1261 0.22747,-2.58451 c 0.16407,-0.76487 0.1886,-0.93449 0.26494,-1.83219 c 0.0429,-0.50463 0.13829,-1.21249 0.21197,-1.57301 c 0.12708,-0.62195 0.30117,-2.20325 0.30117,-2.73562 c 0,-0.32204 -0.0852,-0.49932 -0.27856,-0.5794 c -0.0861,-0.0357 -0.24517,-0.13525 -0.35339,-0.22125 c -0.10821,-0.086 -0.29568,-0.20064 -0.41657,-0.25476 c -0.12089,-0.0541 -0.26789,-0.1525 -0.32665,-0.21864 c -0.0588,-0.0661 -0.18223,-0.15172 -0.27435,-0.19022 c -0.0921,-0.0385 -0.28271,-0.15792 -0.42351,-0.2654 c -0.14081,-0.10748 -0.2908,-0.19541 -0.33333,-0.19541 c -0.0425,0 -0.15575,-0.075 -0.25161,-0.16657 c -0.0959,-0.0916 -0.25628,-0.20083 -0.35649,-0.24271 c -0.1002,-0.0419 -0.26282,-0.14692 -0.36137,-0.23345 c -0.0986,-0.0865 -0.23544,-0.17483 -0.30418,-0.19623 c -0.0688,-0.0214 -0.21417,-0.11892 -0.32317,-0.21672 c -0.13371,-0.11996 -0.27656,-0.18955 -0.4391,-0.21392 c -0.25828,-0.0387 -0.38431,0.005 -0.65105,0.22717 c -0.0852,0.0709 -0.24308,0.16572 -0.35082,0.21073 c -0.10773,0.045 -0.25659,0.13996 -0.3308,0.21102 c -0.0742,0.0711 -0.22308,0.16602 -0.33081,0.21102 c -0.10774,0.045 -0.2656,0.14003 -0.35082,0.21116 c -0.0852,0.0711 -0.23994,0.1726 -0.34383,0.22548 c -0.1039,0.0529 -0.25862,0.15434 -0.34384,0.22547 c -0.0852,0.0711 -0.23978,0.16479 -0.34348,0.20812 c -0.10371,0.0433 -0.26919,0.14958 -0.36775,0.23612 c -0.0986,0.0865 -0.23543,0.17494 -0.30417,0.19646 c -0.0688,0.0215 -0.19523,0.0979 -0.2811,0.16966 c -0.0859,0.0718 -0.26954,0.18802 -0.40817,0.25827 c -0.13864,0.0702 -0.28663,0.16937 -0.32887,0.22027 c -0.0422,0.0509 -0.18643,0.13936 -0.32044,0.19658 c -0.13399,0.0572 -0.30435,0.16191 -0.37856,0.23263 c -0.0742,0.0707 -0.22187,0.16492 -0.32813,0.2093 c -0.10626,0.0444 -0.22617,0.12043 -0.26647,0.16899 c -0.0403,0.0486 -0.19623,0.15037 -0.34652,0.22624 c -0.15028,0.0759 -0.34296,0.19632 -0.42818,0.26765 c -0.0852,0.0713 -0.23918,0.16489 -0.34214,0.2079 c -0.10297,0.0431 -0.25862,0.13831 -0.3459,0.21175 c -0.25079,0.21102 -0.47495,0.22655 -0.84046,0.0582 c -0.17243,-0.0794 -0.57349,-0.20222 -0.89125,-0.27291 c -0.31775,-0.0707 -0.67603,-0.17868 -0.79618,-0.23998 c -0.12015,-0.0613 -0.41878,-0.14942 -0.66362,-0.19586 c -0.24483,-0.0464 -0.64508,-0.17121 -0.88943,-0.27732 c -0.42773,-0.18572 -0.4522,-0.20617 -0.65679,-0.5486 c -0.11688,-0.19563 -0.2369,-0.44713 -0.26671,-0.55888 c -0.0298,-0.11175 -0.11618,-0.27684 -0.19194,-0.36686 c -0.0757,-0.09 -0.17501,-0.28923 -0.22058,-0.44267 c -0.0455,-0.15344 -0.14183,-0.36812 -0.21393,-0.47706 c -0.0721,-0.10894 -0.16956,-0.33048 -0.21661,-0.49231 c -0.047,-0.16183 -0.1462,-0.37645 -0.22035,-0.47696 c -0.0741,-0.10049 -0.16014,-0.28051 -0.19111,-0.40003 c -0.0309,-0.11952 -0.13657,-0.35088 -0.23467,-0.51415 c -0.0981,-0.16326 -0.2095,-0.39399 -0.24756,-0.51273 c -0.038,-0.11873 -0.12406,-0.28875 -0.19113,-0.3778 c -0.0671,-0.0891 -0.16111,-0.29763 -0.20899,-0.46351 c -0.0479,-0.16588 -0.1466,-0.38232 -0.21939,-0.48099 c -0.0728,-0.0987 -0.1712,-0.31303 -0.21869,-0.47638 c -0.0474,-0.16334 -0.14596,-0.38407 -0.21884,-0.4905 c -0.0729,-0.10643 -0.16869,-0.31495 -0.21291,-0.46337 c -0.0482,-0.16186 -0.17486,-0.37785 -0.31642,-0.53971 l -0.23602,-0.26986 l -2.58288,-0.0108 c -1.49326,-0.006 -2.6347,0.0103 -2.70572,0.0392 z" /> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + d="m 152.89933,316.55212 c 0.19295,0.0322 0.55726,0.1176 0.80958,0.18997 c 0.25231,0.0724 0.62876,0.15797 0.83655,0.1902 c 0.20779,0.0322 0.47664,0.11643 0.59743,0.1871 c 0.1208,0.0707 0.38306,0.16638 0.58281,0.2127 c 0.19975,0.0463 0.45308,0.14577 0.56296,0.22099 c 0.10988,0.0752 0.32757,0.17425 0.48376,0.22007 c 0.15619,0.0458 0.35049,0.13801 0.43177,0.20487 c 0.0813,0.0668 0.25546,0.16378 0.38706,0.21538 c 0.13159,0.0516 0.31061,0.15388 0.39781,0.22725 c 0.0872,0.0734 0.24669,0.17023 0.35442,0.21523 c 0.10774,0.045 0.2566,0.13849 0.33081,0.20773 c 0.0742,0.0693 0.20979,0.16362 0.30129,0.20973 c 0.17591,0.0886 0.48886,0.32602 0.87922,0.6669 c 0.30005,0.26203 1.6381,1.60115 1.92286,1.92442 c 0.42143,0.47841 1.02232,1.30566 1.07724,1.48304 c 0.0213,0.0688 0.10767,0.20354 0.19198,0.29955 c 0.0843,0.096 0.19566,0.28265 0.24746,0.41473 c 0.0518,0.13209 0.14849,0.30621 0.21487,0.38692 c 0.0663,0.0807 0.16236,0.275 0.21332,0.43177 c 0.051,0.15676 0.14899,0.36063 0.21788,0.45304 c 0.0689,0.0924 0.16391,0.33473 0.21117,0.53851 c 0.0472,0.20377 0.14787,0.47619 0.22357,0.60537 c 0.0831,0.14183 0.16632,0.40956 0.21004,0.67585 c 0.0398,0.24254 0.13225,0.59884 0.20542,0.79179 c 0.0838,0.2209 0.15501,0.57067 0.19241,0.9445 c 0.1012,1.01138 0.16848,2.29223 0.14003,2.66571 c -0.0149,0.19619 -0.0523,0.72101 -0.083,1.16627 c -0.0706,1.02353 -0.13055,1.40617 -0.2695,1.72029 c -0.0609,0.13761 -0.14426,0.45763 -0.1853,0.71114 c -0.0465,0.28741 -0.12664,0.54972 -0.21283,0.69678 c -0.076,0.12971 -0.16463,0.36541 -0.19693,0.52378 c -0.0323,0.15837 -0.12924,0.40428 -0.21542,0.54649 c -0.0862,0.1422 -0.19467,0.3891 -0.24106,0.54868 c -0.0464,0.15958 -0.12365,0.32254 -0.1717,0.36213 c -0.048,0.0396 -0.16774,0.24807 -0.26598,0.46328 c -0.0982,0.21521 -0.20069,0.39129 -0.22764,0.39129 c -0.027,0 -0.11289,0.12751 -0.19095,0.28336 c -0.13427,0.26803 -0.32164,0.53648 -0.66438,0.95189 c -0.083,0.10053 -0.1767,0.22941 -0.20833,0.28639 c -0.18097,0.32607 -2.06494,2.20815 -2.39291,2.39053 c -0.0542,0.0301 -0.18072,0.12283 -0.28126,0.20606 c -0.35107,0.29059 -0.77794,0.58447 -0.96465,0.66411 c -0.10348,0.0441 -0.23731,0.12643 -0.29738,0.18287 c -0.06,0.0564 -0.2547,0.1666 -0.43251,0.24479 c -0.17781,0.0782 -0.37186,0.18647 -0.43123,0.24057 c -0.0593,0.0541 -0.24048,0.13728 -0.40248,0.18482 c -0.162,0.0475 -0.38058,0.14597 -0.48574,0.21873 c -0.10516,0.0728 -0.35954,0.17128 -0.56527,0.21892 c -0.20573,0.0477 -0.47289,0.14421 -0.59369,0.21462 c -0.12732,0.0742 -0.42378,0.16322 -0.70537,0.21178 c -0.26716,0.046 -0.62485,0.13265 -0.79487,0.19242 c -0.48377,0.17005 -0.93335,0.21562 -2.47041,0.25042 c -1.76934,0.0401 -2.81102,-0.0267 -3.45418,-0.22139 c -0.25232,-0.0764 -0.67734,-0.17619 -0.9445,-0.22183 c -0.28967,-0.0495 -0.57663,-0.13603 -0.71089,-0.21443 c -0.12384,-0.0723 -0.391,-0.16949 -0.59369,-0.21597 c -0.2027,-0.0465 -0.45725,-0.14539 -0.56569,-0.2198 c -0.10842,-0.0744 -0.31487,-0.17053 -0.45875,-0.21362 c -0.14389,-0.0431 -0.35877,-0.14726 -0.47751,-0.2315 c -0.11874,-0.0842 -0.30501,-0.18214 -0.41396,-0.21756 c -0.10894,-0.0354 -0.22893,-0.10157 -0.26663,-0.147 c -0.0377,-0.0455 -0.20358,-0.15104 -0.36862,-0.2347 c -0.16504,-0.0837 -0.35895,-0.21526 -0.43092,-0.29244 c -0.072,-0.0772 -0.15867,-0.14034 -0.19268,-0.14034 c -0.034,0 -0.15728,-0.0801 -0.27394,-0.17796 c -0.11666,-0.0979 -0.28876,-0.22539 -0.38244,-0.28335 c -0.50014,-0.30945 -2.28751,-2.10121 -2.50097,-2.50712 c -0.039,-0.0742 -0.16435,-0.24157 -0.2785,-0.37191 c -0.11414,-0.13034 -0.20754,-0.26575 -0.20754,-0.30093 c 0,-0.0352 -0.0588,-0.11921 -0.13071,-0.18675 c -0.0719,-0.0675 -0.20225,-0.27257 -0.28969,-0.45562 c -0.0874,-0.18306 -0.1974,-0.36471 -0.24433,-0.40366 c -0.047,-0.0389 -0.11471,-0.15996 -0.15061,-0.26891 c -0.0359,-0.10894 -0.14642,-0.31617 -0.24563,-0.46049 c -0.0992,-0.14434 -0.18037,-0.30651 -0.18037,-0.36039 c 0,-0.0539 -0.0855,-0.26198 -0.18999,-0.46245 c -0.10449,-0.20047 -0.2269,-0.52369 -0.27203,-0.71827 c -0.0451,-0.19458 -0.1325,-0.43914 -0.19418,-0.54346 c -0.0617,-0.10432 -0.15736,-0.44009 -0.21265,-0.74613 c -0.0553,-0.30605 -0.16262,-0.77965 -0.23854,-1.05245 c -0.29139,-1.0471 -0.29504,-4.00998 -0.006,-5.11056 c 0.074,-0.282 0.17446,-0.74346 0.2233,-1.02546 c 0.0489,-0.282 0.15726,-0.6706 0.24094,-0.86355 c 0.0837,-0.19294 0.17756,-0.47225 0.20863,-0.62067 c 0.0311,-0.14842 0.14295,-0.43556 0.24865,-0.63809 c 0.10569,-0.20252 0.19217,-0.4117 0.19217,-0.46483 c 0,-0.0531 0.0714,-0.18646 0.1587,-0.29629 c 0.0873,-0.10983 0.1979,-0.31774 0.24582,-0.46202 c 0.0479,-0.14429 0.12496,-0.29372 0.17118,-0.33209 c 0.0462,-0.0384 0.15443,-0.21503 0.24044,-0.39258 c 0.086,-0.17756 0.1817,-0.33848 0.21265,-0.35761 c 0.0552,-0.0341 0.22638,-0.26991 0.62538,-0.86148 c 0.11011,-0.16327 0.26265,-0.3609 0.33895,-0.4392 c 0.0763,-0.0783 0.24804,-0.26568 0.38162,-0.41641 c 0.59163,-0.66759 1.53208,-1.56152 1.84734,-1.75593 c 0.0971,-0.0599 0.27205,-0.189 0.38871,-0.28688 c 0.11666,-0.0979 0.23994,-0.17797 0.27394,-0.17797 c 0.034,0 0.12072,-0.0637 0.19268,-0.14143 c 0.072,-0.0778 0.23482,-0.18654 0.36189,-0.24166 c 0.12708,-0.0552 0.32137,-0.17064 0.43178,-0.25668 c 0.11039,-0.0861 0.28356,-0.18385 0.38482,-0.21732 c 0.10125,-0.0335 0.25912,-0.11775 0.35081,-0.18728 c 0.0917,-0.0695 0.28882,-0.16673 0.43805,-0.21601 c 0.14923,-0.0493 0.3586,-0.1489 0.46527,-0.22138 c 0.10667,-0.0725 0.35685,-0.16957 0.55597,-0.21575 c 0.19911,-0.0462 0.46406,-0.14375 0.58876,-0.21684 c 0.14498,-0.085 0.41108,-0.16235 0.73789,-0.21461 c 0.28112,-0.045 0.71758,-0.1448 0.96989,-0.22186 c 0.28289,-0.0864 0.68635,-0.1577 1.05245,-0.18595 c 0.77071,-0.0595 3.62171,-0.0223 4.07485,0.0531 z m -4.95328,-24.23083 c -0.0713,0.0291 -0.16776,0.15493 -0.22986,0.29979 c -0.0588,0.13732 -0.15416,0.30961 -0.21178,0.38285 c -0.0576,0.0732 -0.14425,0.26908 -0.19255,0.43519 c -0.0483,0.16613 -0.147,0.37966 -0.21935,0.47452 c -0.0724,0.0948 -0.1717,0.29117 -0.22077,0.43625 c -0.0491,0.14508 -0.14755,0.3525 -0.21885,0.46093 c -0.0713,0.10844 -0.16494,0.31453 -0.20811,0.45799 c -0.0432,0.14346 -0.13667,0.34874 -0.20777,0.45617 c -0.0711,0.10743 -0.16652,0.32077 -0.21204,0.47408 c -0.0455,0.1533 -0.1552,0.38148 -0.24372,0.50707 c -0.0885,0.12557 -0.18631,0.3261 -0.21731,0.44562 c -0.031,0.11952 -0.11704,0.29954 -0.19118,0.40003 c -0.0741,0.10051 -0.1733,0.31513 -0.22035,0.47696 c -0.047,0.16183 -0.14644,0.38627 -0.22088,0.49876 c -0.0744,0.11249 -0.17059,0.32163 -0.21367,0.46476 c -0.0431,0.14314 -0.13707,0.34587 -0.20888,0.45051 c -0.0718,0.10464 -0.18087,0.32591 -0.24236,0.4917 c -0.12768,0.34431 -0.26391,0.49221 -0.57018,0.61909 c -0.11833,0.049 -0.318,0.13562 -0.44371,0.19245 c -0.1257,0.0569 -0.42171,0.13997 -0.65777,0.18475 c -0.23607,0.0448 -0.55824,0.1399 -0.71595,0.21139 c -0.15769,0.0715 -0.49316,0.16861 -0.74548,0.21585 c -0.25232,0.0472 -0.57473,0.14653 -0.71646,0.22063 c -0.14173,0.0741 -0.36141,0.14895 -0.48817,0.16632 c -0.19617,0.0269 -0.25556,0.0105 -0.39888,-0.1101 c -0.0926,-0.0779 -0.29796,-0.19915 -0.45633,-0.26938 c -0.15836,-0.0702 -0.33601,-0.18109 -0.39477,-0.24637 c -0.0588,-0.0653 -0.18845,-0.15281 -0.28818,-0.19447 c -0.0997,-0.0416 -0.25495,-0.13772 -0.34493,-0.21343 c -0.09,-0.0757 -0.25175,-0.17449 -0.35948,-0.21949 c -0.10774,-0.045 -0.2566,-0.13858 -0.33081,-0.20795 c -0.0742,-0.0694 -0.23491,-0.17622 -0.3571,-0.23744 c -0.1222,-0.0612 -0.29221,-0.16985 -0.37781,-0.24141 c -0.0856,-0.0716 -0.21187,-0.14774 -0.2806,-0.16926 c -0.0688,-0.0215 -0.20562,-0.10993 -0.30418,-0.19647 c -0.0985,-0.0865 -0.27304,-0.196 -0.38774,-0.24329 c -0.11472,-0.0472 -0.26408,-0.13724 -0.33192,-0.19993 c -0.11835,-0.10934 -0.25247,-0.19357 -0.87639,-0.55031 c -0.15575,-0.089 -0.36212,-0.22879 -0.45862,-0.31051 c -0.0965,-0.0817 -0.26929,-0.18721 -0.384,-0.2344 c -0.11471,-0.0472 -0.26927,-0.14297 -0.34348,-0.21285 c -0.0742,-0.0699 -0.22019,-0.16266 -0.32439,-0.20619 c -0.10421,-0.0435 -0.2563,-0.14108 -0.33798,-0.21678 c -0.17706,-0.16409 -0.51803,-0.27652 -0.70006,-0.23083 c -0.072,0.0181 -0.22597,0.10845 -0.34222,0.20086 c -0.11623,0.0924 -0.29635,0.20353 -0.40025,0.24695 c -0.10389,0.0434 -0.24962,0.1356 -0.32383,0.20485 c -0.0742,0.0693 -0.21574,0.1667 -0.31451,0.21657 c -0.0988,0.0498 -0.28886,0.17408 -0.42242,0.27602 c -0.13355,0.10195 -0.27362,0.18535 -0.31128,0.18535 c -0.0377,0 -0.11472,0.0513 -0.17127,0.11384 c -0.0566,0.0626 -0.2364,0.1814 -0.39966,0.26396 c -0.16326,0.0826 -0.3411,0.19913 -0.39519,0.25903 c -0.0541,0.0599 -0.17554,0.13986 -0.26986,0.17768 c -0.0943,0.0378 -0.24176,0.1264 -0.32763,0.19683 c -0.0859,0.0704 -0.27313,0.18734 -0.41615,0.25982 c -0.35143,0.17808 -0.40066,0.35709 -0.32003,1.16362 c 0.0585,0.58488 0.0849,0.74787 0.24004,1.47816 c 0.0441,0.20779 0.11814,0.81497 0.16445,1.34929 c 0.0463,0.53432 0.14435,1.26423 0.21786,1.62202 c 0.0735,0.35779 0.16959,1.07426 0.21352,1.59216 c 0.0439,0.51789 0.12693,1.17033 0.18444,1.44986 c 0.0575,0.27951 0.0899,0.54667 0.0719,0.59369 c -0.0389,0.10165 -0.34625,0.5102 -0.52945,0.7037 c -0.40067,0.42318 -1.66996,1.88634 -1.95863,2.25778 c -0.0989,0.12729 -0.27326,0.27908 -0.38744,0.33732 c -0.20114,0.10263 -0.3419,0.10591 -4.53517,0.10591 l -4.32759,0 l -0.25508,0.25636 c -0.19362,0.1946 -0.27728,0.33328 -0.34719,0.57559 c -0.0506,0.17557 -0.15174,0.4063 -0.22462,0.51273 c -0.0729,0.10643 -0.16876,0.31709 -0.21309,0.46812 c -0.0443,0.15104 -0.14013,0.35534 -0.21293,0.454 c -0.0728,0.0987 -0.17084,0.3118 -0.21788,0.47363 c -0.047,0.16183 -0.14644,0.38626 -0.22088,0.49876 c -0.0744,0.11248 -0.17067,0.32189 -0.21385,0.46535 c -0.0432,0.14346 -0.13998,0.35374 -0.21514,0.4673 c -0.16566,0.25034 -0.31966,0.84041 -0.27049,1.03637 c 0.0197,0.0784 0.11382,0.22367 0.20921,0.32285 c 0.0954,0.0992 0.29487,0.33082 0.44329,0.51473 c 0.30751,0.38104 0.70356,0.85195 0.95905,1.14033 c 0.0959,0.10823 0.27151,0.30857 0.39024,0.4452 c 0.11874,0.13662 0.30089,0.342 0.40479,0.45639 c 0.10389,0.11439 0.31034,0.36122 0.45876,0.5485 c 0.29365,0.37053 0.98465,1.19312 1.29148,1.53743 c 0.19594,0.21987 0.28516,0.32194 1.04919,1.20026 c 0.28363,0.32607 0.4453,0.56025 0.46715,0.67669 c 0.0462,0.24624 -0.069,1.43256 -0.1898,1.95503 c -0.10576,0.45735 -0.18513,0.98942 -0.2647,1.77434 c -0.0557,0.549 -0.13168,0.68617 -0.50038,0.9028 c -0.13268,0.078 -0.30525,0.20575 -0.38349,0.28399 c -0.0782,0.0782 -0.17792,0.14224 -0.22152,0.14224 c -0.0436,0 -0.18912,0.0838 -0.32336,0.18631 c -0.13425,0.10247 -0.3381,0.23428 -0.45301,0.2929 c -0.11491,0.0586 -0.24211,0.14657 -0.28266,0.19543 c -0.0406,0.0489 -0.16776,0.13682 -0.28267,0.19544 c -0.11491,0.0586 -0.31876,0.19042 -0.45301,0.29289 c -0.13424,0.10248 -0.27441,0.18632 -0.3115,0.18632 c -0.0371,0 -0.12629,0.064 -0.19826,0.14226 c -0.072,0.0782 -0.23298,0.1882 -0.35782,0.24434 c -0.12483,0.0562 -0.29484,0.15881 -0.3778,0.22816 c -0.0829,0.0693 -0.2496,0.17621 -0.37032,0.23747 c -0.12072,0.0613 -0.25268,0.15135 -0.29323,0.20022 c -0.0406,0.0489 -0.17251,0.13831 -0.29323,0.19878 c -0.12073,0.0605 -0.28022,0.16669 -0.35443,0.23606 c -0.0742,0.0694 -0.22042,0.16185 -0.32493,0.2055 c -0.10449,0.0436 -0.23807,0.13278 -0.29684,0.19806 c -0.0588,0.0653 -0.22828,0.17266 -0.37671,0.2386 c -0.14842,0.0659 -0.30476,0.16216 -0.34742,0.21379 c -0.0426,0.0516 -0.19027,0.15101 -0.32801,0.22081 c -0.25103,0.12721 -0.49179,0.38534 -0.55964,0.60002 c -0.0201,0.0636 0.0375,0.46051 0.12923,0.89053 c 0.091,0.42672 0.20183,1.17659 0.24628,1.66639 c 0.0445,0.48979 0.11783,1.03625 0.16308,1.21436 c 0.0453,0.1781 0.1285,0.57884 0.18501,0.89053 c 0.12185,0.67202 0.15705,0.71244 0.6985,0.80187 c 0.21199,0.035 0.49951,0.12329 0.63892,0.19617 c 0.13942,0.0729 0.4581,0.17134 0.70818,0.21877 c 0.25008,0.0474 0.56582,0.14246 0.70163,0.21117 c 0.13582,0.0687 0.45338,0.16616 0.7057,0.21655 c 0.25232,0.0504 0.5879,0.1518 0.74572,0.22532 c 0.15783,0.0735 0.46939,0.16858 0.69236,0.21125 c 0.22296,0.0426 0.56742,0.14773 0.76548,0.2335 c 0.19804,0.0858 0.5274,0.18426 0.73188,0.21887 c 0.20448,0.0346 0.48985,0.12276 0.63416,0.19588 c 0.14431,0.0731 0.44967,0.1688 0.67859,0.21259 c 0.64254,0.12294 0.74433,0.17198 1.05625,0.50889 c 0.22378,0.24171 0.31131,0.38751 0.38035,0.63359 c 0.0494,0.17579 0.14993,0.40128 0.22357,0.50109 c 0.0736,0.0998 0.17237,0.31387 0.21941,0.47569 c 0.047,0.16183 0.14421,0.3829 0.21593,0.49128 c 0.0717,0.10837 0.16514,0.3125 0.20762,0.45364 c 0.0425,0.14113 0.15839,0.38306 0.25761,0.53763 c 0.1688,0.26298 0.18039,0.31088 0.18039,0.74563 c 0,0.42917 -0.0132,0.48589 -0.17344,0.74384 c -0.0954,0.15359 -0.21095,0.40553 -0.25679,0.55987 c -0.0458,0.15434 -0.14538,0.37016 -0.22122,0.4796 c -0.0758,0.10944 -0.17129,0.32557 -0.21211,0.48031 c -0.0408,0.15472 -0.1331,0.37031 -0.20507,0.47907 c -0.072,0.10876 -0.17213,0.33967 -0.22255,0.51311 c -0.0504,0.17344 -0.15258,0.40739 -0.22702,0.51988 c -0.0744,0.11248 -0.17067,0.32189 -0.21384,0.46535 c -0.0432,0.14346 -0.13718,0.3495 -0.2089,0.45787 c -0.0717,0.10837 -0.16888,0.32944 -0.21592,0.49127 c -0.047,0.16183 -0.1451,0.37496 -0.21789,0.47362 c -0.0728,0.0987 -0.17084,0.3118 -0.21789,0.47363 c -0.047,0.16182 -0.14644,0.38626 -0.22088,0.49875 c -0.0744,0.11249 -0.17067,0.32189 -0.21384,0.46535 c -0.0432,0.14346 -0.1394,0.35286 -0.21383,0.46534 c -0.14614,0.22082 -0.25807,0.68182 -0.20287,0.83547 c 0.0188,0.0523 0.10917,0.17064 0.2009,0.26313 c 0.0917,0.0925 0.25646,0.27464 0.36607,0.40479 c 0.10961,0.13014 0.3282,0.39002 0.48575,0.57751 c 0.95192,1.13279 1.72021,2.00509 2.2073,2.50612 c 0.3581,0.36835 0.45884,0.3845 0.94972,0.15228 c 0.18365,-0.0869 0.54796,-0.19765 0.80957,-0.24615 c 0.26161,-0.0485 0.60502,-0.14692 0.76313,-0.21869 c 0.1581,-0.0718 0.49403,-0.16656 0.74652,-0.21063 c 0.25249,-0.044 0.59156,-0.14078 0.75349,-0.21492 c 0.16194,-0.0741 0.38461,-0.14933 0.49482,-0.1671 c 0.44349,-0.0715 0.75552,-0.15395 1.05865,-0.27972 c 0.1752,-0.0727 0.525,-0.16819 0.77732,-0.21224 c 0.25233,-0.044 0.57142,-0.13716 0.7091,-0.20692 c 0.13768,-0.0697 0.46967,-0.1647 0.73777,-0.21097 c 0.2681,-0.0462 0.595,-0.13291 0.72644,-0.19254 c 0.32043,-0.14536 0.51399,-0.13876 0.70759,0.0241 c 0.0882,0.0742 0.19306,0.13493 0.23303,0.13493 c 0.04,0 0.18789,0.0879 0.3287,0.19541 c 0.1408,0.10749 0.33138,0.22691 0.4235,0.2654 c 0.0921,0.0385 0.21559,0.12409 0.27435,0.19023 c 0.0588,0.0661 0.20899,0.16594 0.33383,0.2218 c 0.12483,0.0559 0.29485,0.15822 0.3778,0.22744 c 0.083,0.0693 0.23583,0.1685 0.33972,0.22059 c 0.1039,0.0521 0.24962,0.15034 0.32383,0.21833 c 0.0742,0.068 0.24983,0.17698 0.39027,0.24218 c 0.31371,0.14564 0.4447,0.34704 0.52639,0.80925 c 0.0341,0.19295 0.10727,0.53297 0.16262,0.75561 c 0.0553,0.22263 0.13994,0.81024 0.188,1.3058 c 0.0481,0.49557 0.14495,1.13918 0.21531,1.43025 c 0.0704,0.29107 0.16736,0.92997 0.21557,1.41976 c 0.0482,0.48979 0.14797,1.14192 0.2217,1.44917 c 0.0737,0.30725 0.15898,0.81728 0.18946,1.1334 c 0.0922,0.95582 0.14224,1.03642 0.72641,1.16916 c 0.20657,0.047 0.54559,0.15454 0.75338,0.23912 c 0.20779,0.0846 0.51139,0.17094 0.67465,0.19192 c 0.16326,0.021 0.45471,0.10663 0.64766,0.19035 c 0.19295,0.0837 0.5684,0.19294 0.83435,0.2427 c 0.26594,0.0498 0.60077,0.15177 0.74408,0.2267 c 0.14534,0.076 0.43898,0.16194 0.66408,0.19437 l 0.40353,0.0581 l 0.32594,-0.34818 c 0.17926,-0.19148 0.41773,-0.44532 0.52992,-0.56405 c 0.29977,-0.31725 1.78308,-2.01041 2.01484,-2.29987 c 0.10963,-0.13693 0.32793,-0.38585 0.48514,-0.55317 c 0.15719,-0.16732 0.38296,-0.41782 0.50169,-0.55667 c 0.22778,-0.26634 0.50606,-0.57604 0.86355,-0.96103 c 0.11873,-0.12787 0.31304,-0.34714 0.43177,-0.48727 c 0.53074,-0.62635 0.86426,-0.93285 1.07943,-0.99197 c 0.13805,-0.038 0.90935,-0.0594 2.13917,-0.0596 l 1.92328,-2.1e-4 l 0.28955,0.24164 c 0.15926,0.13291 0.411,0.39003 0.55942,0.57138 c 0.37333,0.45617 1.51356,1.76528 2.01381,2.31208 c 0.2282,0.24944 0.49467,0.54088 0.59215,0.64766 c 0.36141,0.39586 1.44869,1.65768 1.58574,1.84028 c 0.078,0.10389 0.2961,0.35176 0.48472,0.5508 c 0.18861,0.19904 0.38264,0.41763 0.43117,0.48574 c 0.13309,0.18683 0.70197,0.1699 1.1801,-0.0351 c 0.19295,-0.0827 0.54511,-0.19194 0.78258,-0.24269 c 0.23748,-0.0508 0.59838,-0.15906 0.80201,-0.24069 c 0.20363,-0.0816 0.56793,-0.18569 0.80957,-0.23125 c 0.24163,-0.0455 0.55284,-0.14033 0.69155,-0.2106 c 0.13872,-0.0702 0.42623,-0.15651 0.63892,-0.19164 c 0.2127,-0.0351 0.43405,-0.10245 0.49188,-0.14961 c 0.0761,-0.062 0.13354,-0.24233 0.2079,-0.65246 c 0.0565,-0.31169 0.13989,-0.71243 0.18528,-0.89054 c 0.0454,-0.1781 0.1217,-0.72456 0.16955,-1.21436 c 0.0479,-0.48979 0.14512,-1.1334 0.21612,-1.43024 c 0.071,-0.29685 0.16654,-0.92831 0.21232,-1.40326 c 0.0458,-0.47495 0.14263,-1.11856 0.21523,-1.43025 c 0.0726,-0.31168 0.15839,-0.83128 0.19067,-1.15465 c 0.0764,-0.76554 0.18401,-0.9639 0.64712,-1.19296 c 0.10389,-0.0514 0.24962,-0.15009 0.32383,-0.21934 c 0.0742,-0.0693 0.2251,-0.16357 0.33531,-0.2096 c 0.11021,-0.046 0.28022,-0.15335 0.3778,-0.23846 c 0.0976,-0.0851 0.23366,-0.17231 0.3024,-0.19378 c 0.0688,-0.0215 0.20561,-0.10983 0.30418,-0.19636 c 0.0985,-0.0865 0.26485,-0.19313 0.36956,-0.23687 c 0.10472,-0.0438 0.27077,-0.15297 0.36902,-0.2427 c 0.0982,-0.0897 0.2063,-0.16315 0.24013,-0.16315 c 0.0339,0 0.15319,-0.0729 0.26525,-0.16191 c 0.2414,-0.19185 0.40583,-0.20247 0.78997,-0.0511 c 0.15468,0.061 0.47739,0.14784 0.71712,0.19304 c 0.23974,0.0452 0.60589,0.14928 0.81368,0.23128 c 0.20779,0.082 0.55008,0.17688 0.76064,0.21085 c 0.21056,0.034 0.51585,0.12267 0.67843,0.19709 c 0.16257,0.0744 0.48894,0.16909 0.72527,0.21034 c 0.23634,0.0413 0.59131,0.13967 0.78882,0.21869 c 0.19753,0.079 0.56108,0.18152 0.80788,0.22777 c 0.24681,0.0462 0.57221,0.14221 0.7231,0.21323 c 0.1509,0.071 0.48912,0.1666 0.75162,0.21238 c 0.26249,0.0457 0.58835,0.13896 0.72411,0.20709 c 0.6482,0.32523 0.76557,0.2776 1.48821,-0.60393 c 0.0593,-0.0724 0.19691,-0.23171 0.30565,-0.35396 c 0.10875,-0.12226 0.32733,-0.36988 0.48575,-0.55028 c 0.15841,-0.18039 0.35419,-0.39898 0.43503,-0.48574 c 0.13666,-0.14664 0.5904,-0.67483 1.26975,-1.47809 c 0.2314,-0.27358 0.28336,-0.37197 0.28336,-0.53651 c 0,-0.27238 -0.14238,-0.73357 -0.30002,-0.97177 c -0.0711,-0.10744 -0.16459,-0.31271 -0.20776,-0.45617 c -0.0432,-0.14346 -0.13941,-0.35286 -0.21385,-0.46535 c -0.0744,-0.11249 -0.17383,-0.33693 -0.22088,-0.49875 c -0.047,-0.16183 -0.14509,-0.37496 -0.21788,-0.47363 c -0.0728,-0.0987 -0.16861,-0.30296 -0.21293,-0.454 c -0.0443,-0.15104 -0.1397,-0.36095 -0.21195,-0.46646 c -0.0723,-0.10551 -0.16762,-0.31391 -0.21192,-0.46309 c -0.0443,-0.1492 -0.15421,-0.40289 -0.24423,-0.56376 c -0.09,-0.16088 -0.18013,-0.38288 -0.20025,-0.49334 c -0.0201,-0.11047 -0.10606,-0.31042 -0.19098,-0.44434 c -0.0849,-0.13393 -0.19224,-0.37356 -0.23846,-0.53254 c -0.0462,-0.15896 -0.14358,-0.36975 -0.21637,-0.46842 c -0.0728,-0.0987 -0.16885,-0.30297 -0.21347,-0.454 c -0.0446,-0.15104 -0.15438,-0.38391 -0.24392,-0.51749 c -0.22716,-0.33885 -0.22798,-0.69786 -0.002,-1.03083 c 0.0885,-0.13062 0.19965,-0.36901 0.24696,-0.52973 c 0.0473,-0.16073 0.14565,-0.37932 0.21853,-0.48575 c 0.0729,-0.10643 0.16877,-0.31708 0.21309,-0.46812 c 0.0443,-0.15104 0.14013,-0.35534 0.21293,-0.454 c 0.0728,-0.0987 0.16975,-0.30806 0.21547,-0.46532 c 0.0457,-0.15726 0.15993,-0.41442 0.25381,-0.57145 c 0.0939,-0.15705 0.19972,-0.33466 0.2352,-0.3947 c 0.10533,-0.17823 0.57506,-0.39772 1.0399,-0.48589 c 0.23909,-0.0453 0.56507,-0.14215 0.72439,-0.21509 c 0.15933,-0.0729 0.49297,-0.17119 0.74142,-0.21832 c 0.24846,-0.0472 0.56469,-0.14293 0.70275,-0.21289 c 0.13805,-0.07 0.44922,-0.16479 0.69151,-0.21075 c 0.24226,-0.046 0.558,-0.14311 0.70162,-0.21588 c 0.14362,-0.0728 0.46575,-0.17114 0.71583,-0.21857 c 0.25008,-0.0474 0.56498,-0.1439 0.69977,-0.21438 c 0.1348,-0.0704 0.46033,-0.16846 0.72343,-0.21776 c 0.26308,-0.0493 0.5913,-0.14688 0.72938,-0.21685 c 0.13808,-0.07 0.34686,-0.14364 0.46395,-0.16373 c 0.55814,-0.0957 0.61076,-0.12415 0.75448,-0.40776 c 0.17117,-0.33777 0.22334,-0.61301 0.32377,-1.70817 c 0.0441,-0.48141 0.13942,-1.14931 0.21172,-1.48422 c 0.15014,-0.69553 0.2733,-1.75816 0.22573,-1.94769 c -0.0519,-0.20669 -0.24292,-0.40975 -0.51542,-0.54783 c -0.13994,-0.0709 -0.28772,-0.16904 -0.32839,-0.21805 c -0.0406,-0.049 -0.16798,-0.13707 -0.28289,-0.19569 c -0.11491,-0.0586 -0.31877,-0.19044 -0.45301,-0.29291 c -0.13424,-0.10247 -0.27859,-0.1863 -0.32078,-0.1863 c -0.0422,0 -0.16682,-0.085 -0.27697,-0.18891 c -0.11014,-0.10389 -0.22977,-0.1889 -0.26585,-0.1889 c -0.036,0 -0.17541,-0.0838 -0.30966,-0.18631 c -0.13424,-0.10247 -0.3381,-0.23427 -0.453,-0.2929 c -0.11492,-0.0586 -0.24211,-0.14657 -0.28267,-0.19543 c -0.0406,-0.0489 -0.16775,-0.13681 -0.28267,-0.19544 c -0.11491,-0.0586 -0.31876,-0.19042 -0.45301,-0.2929 c -0.13424,-0.10247 -0.27442,-0.18631 -0.31149,-0.18631 c -0.0371,0 -0.1263,-0.064 -0.19826,-0.14225 c -0.072,-0.0783 -0.23299,-0.1882 -0.35782,-0.24434 c -0.12484,-0.0562 -0.29485,-0.15882 -0.3778,-0.22816 c -0.083,-0.0693 -0.2496,-0.17621 -0.37032,-0.23747 c -0.12073,-0.0613 -0.25278,-0.15148 -0.29346,-0.20049 c -0.0406,-0.049 -0.18477,-0.14531 -0.32022,-0.21399 c -0.13544,-0.0687 -0.28948,-0.17272 -0.34231,-0.23119 c -0.0528,-0.0585 -0.19444,-0.15067 -0.31469,-0.2049 c -0.17249,-0.0778 -0.25044,-0.16194 -0.36936,-0.39877 c -0.15975,-0.31814 -0.22738,-0.70341 -0.32746,-1.86535 c -0.0307,-0.35621 -0.11888,-0.91262 -0.196,-1.23646 c -0.19827,-0.83258 -0.19666,-1.09566 0.008,-1.33979 c 0.089,-0.1061 0.28335,-0.3433 0.43177,-0.52712 c 0.29617,-0.36679 0.63584,-0.77268 0.9259,-1.10641 c 0.10319,-0.11874 0.2771,-0.31906 0.38647,-0.44514 c 0.10936,-0.1261 0.29598,-0.33627 0.41472,-0.46704 c 0.11874,-0.13077 0.33733,-0.38903 0.48575,-0.5739 c 0.43309,-0.53944 1.03399,-1.24997 1.64165,-1.94112 c 0.76287,-0.8677 1.07659,-1.23596 1.18603,-1.39218 c 0.14323,-0.20448 0.16012,-0.46572 0.0447,-0.69146 c -0.0439,-0.0859 -0.0963,-0.2325 -0.11635,-0.32577 c -0.02,-0.0933 -0.10721,-0.28107 -0.19362,-0.41734 c -0.0864,-0.13627 -0.19494,-0.37783 -0.24116,-0.5368 c -0.0462,-0.15897 -0.14358,-0.36976 -0.21637,-0.46843 c -0.0728,-0.0987 -0.17085,-0.31179 -0.21789,-0.47362 c -0.047,-0.16183 -0.14421,-0.3829 -0.21592,-0.49127 c -0.0717,-0.10837 -0.16572,-0.31441 -0.2089,-0.45787 c -0.0432,-0.14346 -0.13709,-0.34955 -0.2087,-0.45799 c -0.0716,-0.10843 -0.16099,-0.2943 -0.19862,-0.41304 c -0.0973,-0.30712 -0.1942,-0.44278 -0.39422,-0.55208 c -0.16209,-0.0886 -0.49628,-0.0976 -4.56311,-0.12256 l -4.3882,-0.027 l -0.32206,-0.35082 c -0.17713,-0.19295 -0.42471,-0.46634 -0.55019,-0.60755 c -0.49188,-0.55353 -0.61317,-0.69096 -0.80707,-0.91457 c -0.11063,-0.12758 -0.28588,-0.3291 -0.38946,-0.44784 c -0.56548,-0.64823 -0.73775,-0.86881 -0.76578,-0.98046 c -0.0429,-0.17107 0.12913,-2.1261 0.22747,-2.58451 c 0.16407,-0.76487 0.1886,-0.93449 0.26494,-1.83219 c 0.0429,-0.50463 0.13829,-1.21249 0.21197,-1.57301 c 0.12708,-0.62195 0.30117,-2.20325 0.30117,-2.73562 c 0,-0.32204 -0.0852,-0.49932 -0.27856,-0.5794 c -0.0861,-0.0357 -0.24517,-0.13525 -0.35339,-0.22125 c -0.10821,-0.086 -0.29568,-0.20064 -0.41657,-0.25476 c -0.12089,-0.0541 -0.26789,-0.1525 -0.32665,-0.21864 c -0.0588,-0.0661 -0.18223,-0.15172 -0.27435,-0.19022 c -0.0921,-0.0385 -0.28271,-0.15792 -0.42351,-0.2654 c -0.14081,-0.10748 -0.2908,-0.19541 -0.33333,-0.19541 c -0.0425,0 -0.15575,-0.075 -0.25161,-0.16657 c -0.0959,-0.0916 -0.25628,-0.20083 -0.35649,-0.24271 c -0.1002,-0.0419 -0.26282,-0.14692 -0.36137,-0.23345 c -0.0986,-0.0865 -0.23544,-0.17483 -0.30418,-0.19623 c -0.0688,-0.0214 -0.21417,-0.11892 -0.32317,-0.21672 c -0.13371,-0.11996 -0.27656,-0.18955 -0.4391,-0.21392 c -0.25828,-0.0387 -0.38431,0.005 -0.65105,0.22717 c -0.0852,0.0709 -0.24308,0.16572 -0.35082,0.21073 c -0.10773,0.045 -0.25659,0.13996 -0.3308,0.21102 c -0.0742,0.0711 -0.22308,0.16602 -0.33081,0.21102 c -0.10774,0.045 -0.2656,0.14003 -0.35082,0.21116 c -0.0852,0.0711 -0.23994,0.1726 -0.34383,0.22548 c -0.1039,0.0529 -0.25862,0.15434 -0.34384,0.22547 c -0.0852,0.0711 -0.23978,0.16479 -0.34348,0.20812 c -0.10371,0.0433 -0.26919,0.14958 -0.36775,0.23612 c -0.0986,0.0865 -0.23543,0.17494 -0.30417,0.19646 c -0.0688,0.0215 -0.19523,0.0979 -0.2811,0.16966 c -0.0859,0.0718 -0.26954,0.18802 -0.40817,0.25827 c -0.13864,0.0702 -0.28663,0.16937 -0.32887,0.22027 c -0.0422,0.0509 -0.18643,0.13936 -0.32044,0.19658 c -0.13399,0.0572 -0.30435,0.16191 -0.37856,0.23263 c -0.0742,0.0707 -0.22187,0.16492 -0.32813,0.2093 c -0.10626,0.0444 -0.22617,0.12043 -0.26647,0.16899 c -0.0403,0.0486 -0.19623,0.15037 -0.34652,0.22624 c -0.15028,0.0759 -0.34296,0.19632 -0.42818,0.26765 c -0.0852,0.0713 -0.23918,0.16489 -0.34214,0.2079 c -0.10297,0.0431 -0.25862,0.13831 -0.3459,0.21175 c -0.25079,0.21102 -0.47495,0.22655 -0.84046,0.0582 c -0.17243,-0.0794 -0.57349,-0.20222 -0.89125,-0.27291 c -0.31775,-0.0707 -0.67603,-0.17868 -0.79618,-0.23998 c -0.12015,-0.0613 -0.41878,-0.14942 -0.66362,-0.19586 c -0.24483,-0.0464 -0.64508,-0.17121 -0.88943,-0.27732 c -0.42773,-0.18572 -0.4522,-0.20617 -0.65679,-0.5486 c -0.11688,-0.19563 -0.2369,-0.44713 -0.26671,-0.55888 c -0.0298,-0.11175 -0.11618,-0.27684 -0.19194,-0.36686 c -0.0757,-0.09 -0.17501,-0.28923 -0.22058,-0.44267 c -0.0455,-0.15344 -0.14183,-0.36812 -0.21393,-0.47706 c -0.0721,-0.10894 -0.16956,-0.33048 -0.21661,-0.49231 c -0.047,-0.16183 -0.1462,-0.37645 -0.22035,-0.47696 c -0.0741,-0.10049 -0.16014,-0.28051 -0.19111,-0.40003 c -0.0309,-0.11952 -0.13657,-0.35088 -0.23467,-0.51415 c -0.0981,-0.16326 -0.2095,-0.39399 -0.24756,-0.51273 c -0.038,-0.11873 -0.12406,-0.28875 -0.19113,-0.3778 c -0.0671,-0.0891 -0.16111,-0.29763 -0.20899,-0.46351 c -0.0479,-0.16588 -0.1466,-0.38232 -0.21939,-0.48099 c -0.0728,-0.0987 -0.1712,-0.31303 -0.21869,-0.47638 c -0.0474,-0.16334 -0.14596,-0.38407 -0.21884,-0.4905 c -0.0729,-0.10643 -0.16869,-0.31495 -0.21291,-0.46337 c -0.0482,-0.16186 -0.17486,-0.37785 -0.31642,-0.53971 l -0.23602,-0.26986 l -2.58288,-0.0108 c -1.49326,-0.006 -2.6347,0.0103 -2.70572,0.0392 z" + style="fill:url(#radialGradient5881);fill-opacity:1;stroke:#000000;stroke-width:1;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" + id="path2248" + inkscape:connector-curvature="0" /> From 8022fbc1334ba503a8d7d9709efc52e22d37a73b Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Thu, 4 Sep 2014 00:15:29 +0200 Subject: [PATCH 121/203] OP-1222 Revert : "No-sensor" icon available if needed. --- .../setupwizard/resources/sensor-shapes.svg | 433 ++++++++++++++++++ 1 file changed, 433 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg index b1ff7d6ea..463ea9862 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg @@ -2773,6 +2773,439 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Date: Thu, 4 Sep 2014 09:50:15 +1000 Subject: [PATCH 122/203] Start implimenting new Artwork from Laurent --- .../setupwizard/pages/airspeedpage.cpp | 2 +- .../src/plugins/setupwizard/pages/gpspage.cpp | 11 +- .../plugins/setupwizard/pages/summarypage.ui | 7 +- .../setupwizard/resources/gps-shapes.svg | 108 ------- .../setupwizard/resources/sensor-shapes.svg | 305 ++++++++++-------- 5 files changed, 172 insertions(+), 261 deletions(-) delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/gps-shapes.svg diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index bd7af6a0c..5e7c90f62 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -29,7 +29,7 @@ #include "setupwizard.h" AirSpeedPage::AirSpeedPage(SetupWizard *wizard, QWidget *parent) : - SelectionPage(wizard, QString(":/setupwizard/resources/airspeed-shapes.svg"), parent) + SelectionPage(wizard, QString(":/setupwizard/resources/sensor-shapes.svg"), parent) {} AirSpeedPage::~AirSpeedPage() diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp index a7f3499f0..6d53cbda6 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp @@ -29,7 +29,7 @@ #include "setupwizard.h" GpsPage::GpsPage(SetupWizard *wizard, QWidget *parent) : - SelectionPage(wizard, QString(":/setupwizard/resources/gps-shapes.svg"), parent) + SelectionPage(wizard, QString(":/setupwizard/resources/sensor-shapes.svg"), parent) {} GpsPage::~GpsPage() @@ -47,30 +47,31 @@ void GpsPage::setupSelection(Selection *selection) selection->setText(tr("Please select the type of GPS you wish to use. As well as OpenPilot hardware, " "3rd party GPSs are supported also, although please note that performance could " "be less than optimal as not all GPSs are created equal.\n\n" + "Note: NMEA only GPSs perform poorly on VTOL aircraft and are not recommended for Helis and MultiRotors.\n\n" "Please select your GPS type data below:")); selection->addItem(tr("Disabled"), tr("GPS Features are not to be enabled"), - "disabled", + "no-gps", SetupWizard::GPS_DISABLED); selection->addItem(tr("OpenPilot Platinum"), tr("Select this option to use the OpenPilot Platinum GPS with integrated Magnetometer " "and Microcontroller connected to the Main Port of your controller.\n\n" "Note: for the OpenPilot v8 GPS please select the U-Blox option."), - "platinum", + "OPGPS-v9", SetupWizard::GPS_PLAT); selection->addItem(tr("U-Blox Based"), tr("Select this option for the OpenPilot V8 GPS or generic U-Blox chipset GPSs connected" "to the Main Port of your controller."), - "ublox", + "OPGPS-v8-ublox", SetupWizard::GPS_UBX); selection->addItem(tr("NMEA Based"), tr("Select this option for a generic NMEA based GPS connected to the Main Port of your" "controller."), - "nmea", + "generic-nmea", SetupWizard::GPS_NMEA); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui index 3e2fe7f7d..716956709 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui @@ -74,13 +74,12 @@ p, li { white-space: pre-wrap; } - :/setupwizard/resources/bttn-illustration-up.png - :/setupwizard/resources/bttn-illustration-down.png:/setupwizard/resources/bttn-illustration-up.png + :/setupwizard/resources/bttn-illustration-color-up.png:/setupwizard/resources/bttn-illustration-color-up.png - 100 - 100 + 150 + 150 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/gps-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/gps-shapes.svg deleted file mode 100644 index 350e30e98..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/gps-shapes.svg +++ /dev/null @@ -1,108 +0,0 @@ - - - - - - - - - - image/svg+xml - - - - - - - OpenPilo - Eagletree - - - MS4525 - - - OpenPilot - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg index 463ea9862..3ca39d3b3 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg @@ -1238,14 +1238,6 @@ stdDeviation="1.7473229" id="feGaussianBlur5847" /> - - - @@ -3324,7 +3316,7 @@ + + transform="matrix(0.52050376,0,0,0.52050376,117.81395,605.77767)" + id="g13585" + style="opacity:0.46992481"> - - - - - - - - - - - NO GPS - + id="path13587" + d="m 71.978864,612.10223 265.670576,0 c 40.4642,0 73.04008,31.15598 73.04008,69.85644 l 0,273.09908 c 0,38.70046 -32.57588,69.85645 -73.04008,69.85645 l -265.670576,0 c -40.464203,0 -73.0400773,-31.15599 -73.0400773,-69.85645 l 0,-273.09908 c 0,-38.70046 32.5758743,-69.85644 73.0400773,-69.85644 z" + style="fill:#feecec;fill-opacity:1;fill-rule:evenodd;stroke:none" + transform="translate(-4.5344602,0.00674438)" /> + sodipodi:nodetypes="ccccccc" /> + + - + + + + + NO GPS + + + Date: Thu, 4 Sep 2014 09:54:03 +1000 Subject: [PATCH 123/203] Remove old button --- ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc | 1 - 1 file changed, 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index a47c02b4a..216a1ebcc 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -39,7 +39,6 @@ resources/fixedwing-shapes-wizard-no-numbers.svg resources/airspeed-shapes.svg resources/bttn-illustration-down.png - resources/bttn-illustration-up.png resources/bttn-illustration-color-up.png resources/bttn-illustration-color-down.png resources/bttn-save-down.png From 3e6bb1e09d7674c9567889fb902fc15d9b5b8ef4 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 4 Sep 2014 09:54:26 +1000 Subject: [PATCH 124/203] Remove other state from qrc also --- ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc | 1 - 1 file changed, 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index 216a1ebcc..1eee82963 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -38,7 +38,6 @@ resources/fixedwing-shapes-wizard.svg resources/fixedwing-shapes-wizard-no-numbers.svg resources/airspeed-shapes.svg - resources/bttn-illustration-down.png resources/bttn-illustration-color-up.png resources/bttn-illustration-color-down.png resources/bttn-save-down.png From 4c5afba2aa4065ba6377d510e26b7d69d42ef456 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 4 Sep 2014 09:55:05 +1000 Subject: [PATCH 125/203] Actualy Up file deleted --- .../resources/bttn-illustration-up.png | Bin 8406 -> 0 bytes 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-up.png diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-up.png deleted file mode 100644 index 5013d30b2a74b35f9eb54961ae0c5133c46a67d1..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 8406 zcmbVyWmFu^)-DzZ5Ih7K0%Xt-U>ID3%itPZhQV!y!2<*d1Hps46C}6=C%9X1CpZZX zAvn3@ob#T0e|+ovaeH-lRafo(>|MK_s_s?Qq3Wvg1bEbVXlQ5z5Cs{{hZON}IXuRG zxL5z;FL_9)TxIoKwcu8+9#EtunxqBX+>##R2(`A2h*lO#!>ZvFT z!{Cmb(7!UAo{oQ^(9lH1JrPity`?L?xuvzOlNj)*`74m#)Kgiod28^%Q;paI|!V(tA2OIJpRWiUI$HEBuiETMPoy|4YQxUJUqe zr}R|R>80UFOL{&|9u6267);O4&k5$`?!4aXN@?T&lm;VInA!Hy=C;|lL@a>XzAn%kr4wv)NoqZS_sQZ$qI0RW#nXdWx=vwFj!KWi(6J!QdSZyz|YSMmi-6g zf6@iZ^6_%<%E`*gf%(7>+EM~MLV}WV0@8xq{6ajkeE;Y|oLpR?PB6=V?Akuq{g1B9 z|Eeo2jkJWi!jal=xWhjTP`81*!d-0O2zqHPetK3FD9qOBZ^6sI9rW+^%2*<8-7PKT zkZ?!(e??f>_J8nzi(Bx4KLWg50^D5uf?%*9mmrTMza%%W9G5gVw=6&KKe`tGKT!ic zI0O1ikN<}*{}erN@Nf3NM%8pV~Y80vW1i^ch&YXTIm>tvYTcpU3>hid|H7bPdrf12an( zAhDK1i6ffD+R+C3`m$B|0jOcQk&zJ{cBa{>DWBU3C6Mn}bt-Ff#uTRwO+#Vk+rh=L zu_IJ=cJ>ts3CXx!of(=Y%QMxq0IZe7#6%z;A9+ejN>;jv$KlAuiZ`fGjNX!&QGMd{ zCDXB76pfI$pde*JLPE=0K>;(qzZI4`Fs6NBfg08u5fBp6cbk}NjfL)ruG#Q~6qETr zp3}I=^^K?JCB>9F1cIBaAYC}A-@b=IY{^X(ugFA0LsRK};gtXBli20y5GYP~I+U>r z!X9A$BTiGZWcrMOfk8t@2i4Rh%;_bC^Nbr5lTADpdco@k)=`YT%qvoi%NAl{o?^j? z2|YziJ^Q)0#}PYw9{glS=p>Vip4|XT2{;i?Ba!m*csCA`O7H^~D=K--KIO)EobgaC zGxs5q@|6~wc9G3TVV9B-rAH{eueJcff=n4nXR0w5ml>dyncr|KKW#auYJDB=myc+f zGWk+M{x;UM`=r;Fi?lw+2ha5E)9Gg~JM~L8uiOau<`Uy09dGW5@adY!VDe8ImrE+wg0H{{hL^NwRW}#Gl201rxPp zp!4;cvmYeo{_J#RmPMivIg#byLyb z?d+ZnjZ3j?+TC%4Oyk;2HL-5t9TR${sLy!F=S#{nCB>i3=x3$Nt5Kc3F}@4nNrMop zZ3e!nH}nUcOrpP&>YXnxB^!=1ZPnSH*1yN&+k`|!P`WdTU-F^7xInn{W~1jQpO-Xu;qiq= zmo}SxqJjadgib`$PzlPhOI3EuwEH3m%5NmTjewZs*r?%KVP>dr^5+EU7sXw3tm2zH zJA2lyp;$cf=Uu$akw+D3?U_>!he*~b!hX&(d)kEwcYHyir$&=aevUv zeNdz!**K#{HHA!%enCkEN@v4B86fgFdP%%SzR2Dd|3k3OheYrB&4D-y0vbW$y1F{i zN;ZBQVFrCArpLeBq?ckG6t>v(Uhy_)Yoaz`)-j1GAz{pbxu#!%b%U7%<+z{`0704D z;B?-x)dZ<-O*uLl>;{VXAfReVk((P;SN3Ix)Qi6!P5iz(LooWCW-K z63Znf2Bd6^Fw8dA@$25>=+4?Dmhuty3#NrMTw+CpJxBYb`Rzvw2`R^`Vr@2>*FKbn z^-jKpJw#6v<2{?0(EtFz2x;m0g}WRboP|a-rjJph=gCuV+8B-b#;VO>b~V5p>nG2X zoS5CCz5XOU(O>@b%=XoyW4uzB#gqnd@;Y+#8bSpq?cyDXo5pA%%hX}l5CnGES2w+2SnD#VE-n#en080i7 zjl(7}@fnr&WgYQV94Yp1=}By}-Xisu8ve}UuJG%tnBuQBJy)LV6-Q=2`w^m|9@q|! zj!(u8A;Rc&c`T(=yKH+_?54crBawB2-oM#F^}1{)M<}i1RGx78`HSifsi{HLk54ZEQ}^VGd%C!%IhF)64L0KJt7c&VGBFSxl`F|O zpOVgTDVhUk6k)pwR~iz2X-%oL>0-5GgoXVZJa6Kz z`nm$vV?-qqgV$EZSQ!dFOxViGTN=bQPy>xBn}2A|Be=lCS1cJX{f5NMZ(zl#_v+Wh$H`!KTcT=HKGVi(hIJ$S-ESunmY5|*cbSqd)$)6uGrg5H zAhHIex|ty-rAZwuC%>frHUF9IJMGG=stON##39Wy|9CPX(P}NnPaXIbei1vg8KG^y zZ_iF$=7l`>@(7A-Dg%1o3}Bwb1qYuS;XYkKb7_Hk$EitfeIM;`sf}5WEM(4Ws-~gf zj6XvHP#AE|^a!ttQfa1|OWxu2#Z1K0``0GQYkX&VvCU~iZqbq3@`~no_=v7{36^{- zo#U;N&UFLPyJ(`d>@R`cih;R<*oSlWG{!0MiX{7=R*(E^y27&ggWQSWdIa%nYu>;NtpWjK$O}AXW#O26V}nh1FPUcXz(ZAAXFnPkVpg zHS^o(K&7&k`rJGD{GOD&rOCoAUV1db&(VCwSj#yP0eSDe5vpHR#17&sL9OKNNR)~3 zyrGm%O{I3`7a{tV)2gDx_R8LA!qA5s70d!WosM@`^-=0wfqBg}+q^u?0%N-zrVcYu z3Xrb9diApRmg<`);+mN8xp>I_t>ywNzK6A8ckqogr=y&+vvc$uXwi|BlKOjSExy~5 z;{$n~DpQesv+A1I>Lhi5&SWd^4N)NEs00x$@t$(f4Ae+*jzmUu}8z4RVy&M+eT z8k-;}>!h}5rs$=}@pqEx0mbra-w($8r1GZ7kp*^ck#&@GTkm6YG45}R6zC!%2|EkL zpSKq@JSq6u@tE-VAH4Wl#^l?M;siT+4Bb(*4hIt4FsFE&Ms8GEmRF5c5`p<^IzWWlx zU;UUJcxUgMr!u@rPmZEzav@e@5tKMZ#>SxlR@xex-viw+PNX&z&ieEb@ z8$d_iJ`gX3ydWA+-jt3deV9|GOtm*D)F!QHi+wwy^|k;jtvy^1DN> z=;6()WFPR`$;arax;htbp}!#N*1eA|Fg$}M0KIKHj*~y>RkBDzdb*GA5Ckjxc#qMA zT`v~j`Jy4frl_JTrG;Bz)2@wKA-swaqKKk#={xT`BZ`#OvGf9z(KB*0vl?v=XfLJX zV&+tT=?vW`5{X*>K`_2J2k%w;FL41Plca(sx%W?lve!^vu8PPB; zMcAA=++@cbBIdzlfk(c6!2+B3fUev$ZDly#O6|W)jlcEG)D}$J#DGUM_Ms=|*IEB7 z_MOptqq=gRG?D!Vs|)xR zws!07MK7T&?lg~6w0tFJzHn4$wk@$F#%%QUbnH4yn4NNwD82LROt(v&8f@`+$cfz( zVKr7K)!ey|OUZQLjC*hp)Gs0MK8%Bdv!&cr;TtuB{>QNu0SunLAZX8mXSyH@bmns~ zTt#`b>B9}hA2N@q@Zj*gM4TEXP5XV7kqP)&Qa|xe`|y`llA`;}gkeNPM=0MrqpCj^ zFYJeKUs7EyU+2xzR?)I5Ftq;2kj?)+K#us5u#q7?(tZR90%idNQan7S;o1C@`>nr-x(pXm@n!F8P zS%QfgDD2;f1i6V!dbJza?)5VWZ!)Mm#GNv7+w)Fo=ax5BFCQ7J<<#{G_iHO2VyC$9 ztrzIU9O2~(vOq3<$ruoQABcT^`2wr)+05q5A=rx0M|M8}UX`LRuCQDrbCti4`>`$~ z4%TuH8cA(N6_hsG6zz+gD@sqc+b@vbdnlEK;)jvQ?Mry%X)%Cp_~8&^q)%f;13zS40U zAmgDYCdAjx)2 z196amo*Eq3a5mcOdiR~!SXm4eEKGALZ|KN`iQZQ+^3Y-9{#T#ZzkWozsaJ8UEr~dz z5si>|iU}wCmW&4IGK6ib(|=zR$vfHHU&DsU`vhvLL>~S&QT_Qt#w@1CZZPEtViD6$ zt32E30r7ZJTHAtc?Gjdz>LKRJDuy%kRkg)YBGD-Pmz%pVLKFw&Q+xE;Yc?)y(5_NE zuiXK56y+-Y5Nt`e_#{)kfU?k(xg;dvC-S;rpTWGFUp0?z4f@qo$F{tvKP`f6TNDFQAJxmkF7Oao6FEUu_;3zG-NA?U0LDwPZ#~~+B^;hl2abNHI08iM62nUu z5X6f_JIC(1H%(9v15Vlo7+S2VaWDubd`B%P+W%gh$HjtJTiN`pmzQw-6TO@YSRu&y zW9Xp1>5&*u=2y|$#?W@M>vvaOt5qOAK#uQ{H^2Wj&^$=OIf6u-+3IAE)N0(P{(v=> zvPQ9FZ&B1k*8x5%k*l?Xe`TFza((l0g_A}iSMpBu>U?FBePuNLTfpT9$n?ki>-VIc z7|SZZb&S0~jeR3Ap%Klk)uOoC$$E1Dj;9;q?1;N~a+rda>L^zEsny?PG`Li2UN-nO z5lwSD)z|$sXlWGLc3X9*I739&v<9rf-F^Is|5aI0Kwc~Lv>QRNJBIJC1Nf2$UK=NM zchC(I&4W2><3jt-&`1b@Z%mN*ZEuC{!QLGc*^}(l#mI)2(zerlZ;A1SK382FUlHyF z*A-PH?8R{bhXH99)>MNEk3z15zwcg=E{T7Er+I^o?M)5pXyE0L_GRU}H?#c5Rio5& z3yv*65xNGhuC;3|`=hm`{X3I4ct+<I}w+T zz(-bMpE{*iG$-LgoQE9!+}ITQSCAf9Y z(gAuFcZ(t@Z+?5+IG0O+4t`B21HM(Ln7%9Le|)&rznES7;*j?ZJ9V_1NYu&c!>qjB z-r9WcpOXc>TR!P7?eOsl*FF61`1p?4_t(x#V_`AZfwyLFGT#vu&^xcooXDE*4)%~$ zu4P>ulLtJBx;yCHXeJL{(U*dlRYdN9&|bs2i@@ z?Cx#s6rNh&Uym!Wr;9|0H~R+9PZT$?H_bG+fXN-m;%dw6+ez7j?M{Fk}r z>&O^ZK86bGG8}hooz%w)__cp_A91=d#;_Iq+%24Ry)Ku~meZ7liyDV7l4g=6#l(|T z3ZW7%$7Y=ceb`pBF^VhJlmiu{c2n$Q;-9~qfBgH~h4i_!?{hB^jGkYU^%OHIXO>CB z0lss$q?8i<(*1FnRm4+|%t2!6Ms{r1MyN#T+%k^2_(v`$fEx4{B z;r{bHDRp&Cl1fZdC3>r3_h&Odo+_vGXZ!=W}$mG>3piV zF`)4$SMuGjNwu@pS^ayoYHx*0=}nJS-;3+O`9!@Ure}6Jh8=iy<0?+5)Z7v8D4vod zWZK>#GhVnxlkN6^eL_1xWfN2N?e?pC$iqbvAph*_;_vg7t#JnRtr@ohFF6B+pF$MCCO>?A)j~MhD zg&r>t-lY7VE>`zN)@>!7y@&Pjt%9HRt+OIyV%f^j5ew%%DTA~a*h7;s)9C&cZ3=0y znxDv^xcrk}eXp|irDi_i9onl#97bO8z&yQ+^--cR&-Bihv>(<26Y4MO`z?Y5Qm*8Ca>6*U`Ac(bc=b|YcV3=U7`7iL47zj|0?bJ;Re ze+|w`^tOS7?S`~c(Og0?-*$a7dGFm9a=Ov1YGK?tNEZvX)ZeT0@WFOJ;Tj|}|G@`Y6kNPuv;n-7y;{4Bqo|zSXbtF=5z#mSBRe{!vs*M%;#~ zeY>bpD=%APU@<<+b|>W1ui@=WEh7U6>PRdxd=8OC+XK>1DpJdq?vnNKJqqG#`NE9u zVq!pqVA5>;~LvW|Sa zo%CK`)c1JDwhUul>7ENCeD$7u^3N~6v1XV8Tn77sTj-q&mRR|xGQ#)s;mRbNX~@z#gPC2fDx=}Kp?=?J=^OBIW2mffP1yx6zCeuJCUw%wf-(*@3Et%SjTS8 zwGXYO3lKsbla%%)!4+^}n{NGC)f!C!{UG6$?us5)GmpZEHU%U?;=mX%s}ruB=?uWe zl(+BF@;;!N{ZXU>_Xy!1OSKyl9MgWT#I-0@|Bi9ny^xc~oZW(!p+Fj!_ud19?v(3UK4c~KX|(wLr8XU1mXI_{8X+ zhOtm82$~j}IuJu$0m(pbDQBh>$v7i5`vL*9B`uLhX9Oe8IlLl)XlWL`z2QYwaxr$~ zhQ$T#_IE=H_{R7Mn~)=nBY-lxmBVm<1a*~NG3$Mh299P-w}C#|{!_FxS+pM!{`S0V z_K$LhyVL0XamXx%$>gFRwE%E5o`j7mkh(orFe_1r7*|j8s$-&3%9QnWZ=>c*l*tIa zs*1!z#dxf;$4Wp)$%H?C&@M^9CAZ7@L)*RWzW zemf87LqR();U~T{gGk~M)s03Cpk`9yliHns@VU@BX0~2fkYQc? Q{nG# Date: Thu, 4 Sep 2014 09:55:27 +1000 Subject: [PATCH 126/203] Actualy downfile deleted --- .../resources/bttn-illustration-down.png | Bin 6683 -> 0 bytes 1 file changed, 0 insertions(+), 0 deletions(-) delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-down.png diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-down.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-illustration-down.png deleted file mode 100644 index a4402d5b029d27f465bd03949de874d7dadc0b89..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 6683 zcmbVRXH*mIwnhj@kuDts6Ql)5LP_W~p-44EDWVV{bO;ctAQ*}?=^`M#i6~8xjx^~4 z0@9>PlOj!;6orf5`Mz`SkF(B?J8Nd%GJ8M!dH4J5HEYd88tQA(Qgc$1kdV-7Ya!7W zt=q-rOi6KZf4dKVebI1uqD(xE@V1^lSPvYDstw)>$EWRrwZoxtSQ|h09-IOR37NeE z#>CS^Pgl+w?;?)0=FBQfqV`&ia=v&J*b|W zI?mof>wyQ(=z%`Q`hkb#Znj$oVP)|H75K=>M690Qvqh z@pMuI{)?1}o*|z)-UG)cEiNf$4TZt@;Bax6lr$U;6XlbD!XzNjixVyelaiB$%Sj;k z{yu;g(L8Ky<wqtxR0bb-op+8la-bIgCQXyc3~k#@N@OV z`ii*{K>r{haRh4*2RBa#yer=yM64Cw%Tp0}!Sr8CaBZy%X1YSH5w{ftML#d$=`I=biQli@$G9I(CZ6Sz42li#t56L`&B3rQN2p^_s0yW>^~854xJ0P&BPg>fT z3RC*puSnF%YVsv?GizldvoPGhA6(MTG6VS`bArL#emBDa!oA*F*0=qg=T$4kIl zj#jS{kZF+v=0c3O?G#_4;mjU{?586|Xpmo{H&|TwDTgkfQ98dLw_iP42)CD`%U`af zjRB`oCksizDay?XGmxD6d>rCP_H?qyb_r>-)(FO1Y>YM(PeMUDq*)63rM=1VBFm4N zyCd>s4Q%tSqs7Nx8QvpBjl=;wLLEk5bY?<_UVWBh(0Y~V!;?CBm2%W1_kbLweci(d zp9hs^iCQ4-k4ZCaYa3%6J9JUm+xftIE5Yp@tT~p;Nk7xEE6eoPW2SC%@_|VkifH8c z`Qp8Z`e@79nJFklyY&?Eq^;%AmYe%qyRJnhG(!MC_iMz41~Cj=@?2JViB2)5*i63D z43r@Hn-fqtS;?8`S)!*nupZvn8Yj0f_$>R!aC?IN@;X3Pa0WA3?a})BQygli6Sq1# zOM1+qO<(yd`JsKZK-=xgaXqcJe`qX#X4Mv#!;dH&iRU z$?UD6CJo(pLi`r=FdV6pi?`ofhkxp@YMuOGvfstX-OOI(v-SPcZ16iFJt<#D>C3a~ z3i6GY`*iife%Cegw4d#KZ##?4A7W=-4O?SAwZAb$YH+X}%)&+QI4bW`QYYV6njQ^+ z15SP(vQ&o{AlDPR7U$FxRyUU)U5k5Xcgn0m8yubg7@B-DMod1${fCC=#_d&bL{Pa;mNCjBt%3jJ@tY{VOb2)EI@ixiHh>Ztc3( ztwKI<8V~brq432NromoRzD793p^g4&tonR~{dx<31jY9{!PC5O3%2>^rQzk4GqW_# zQ`4AOyKtr6WKB!Qykkl3&2;OvMh+SOd1@t#cT8_;TwBLFLU2Zoh1?hs8$pW@2?U4Y zZ-v3m_n?NN+I9@LG6BE@zC0o4<9cfs1(7N$Aw{av&RdGOeHh5G|DAk=(v8C ziFR8+B&oAw?0TlHgmj{Fg~XR`Dv58N-5*}1Ym?>lI?v0XP>n=y$YZ#aJFJB{IxK1A^ zVYe)WBs>=Yx4-#tyT>WD=7jGj##pg@iRBreJx;4?iBa6#pmU_|{A;>$91vV%D41wX zG$_(*&8mvtiKygs7}w8xN1a~`6{Ovp&BhQL8-tmame{`Y>}`y&>ex2-_9qB;7OQy; zwT&?u(C=tK@QB)X&b?|4RK>C~-ap`Hvg}l5DMqh_;tGXdJXwu;L%bi~v%kI9-9y=T ze8^U?{BdZcm|4ecZ`H;)!lEflV56(Z20PEI=?)V}V~uI8j8U{zV0+{(hgNbKFo@7f zCfUvvGWxT`C_vib2N&L)BC3jPo7G1d0VZ$is=>; ziY^zYd%y(>Km4q9FYvlR&=2}8o8|BKoUC!N(v@8~b*0i%%D%rul`II=t&~smiK-gv zwgFfBMrGLt8^Gq7iY9=wZ<|PNTIDdNI-U)4`SH|=k}K{RfPRzu@FZs+je^$?jl9hT zlHYE0N#;|4zzw>Y=$uDg)q@0SuT#}07P`64O4wD zRnD@1#GYC8@wGjbYWL<_EEYbNyjY_sDpj zC&wgehL4%-Gz%YD_UM=9<7FfW)Nd>|8J({*^%Y~d-V>}(ypV|UG3V1YMzRXW-&cfO zrdmhP`44&?h}98jlREpr1VLAR4nbnvac#?ZLuCc8pCpS#x#E+lp63iEmupy$mO276 zEXIR3e|}$!F58U#YK2Ziy)p$`r_!^gKW&Z5@+=-9C3@?X{y6nH|8O}QqOsp$MtbN1LP+Ab$e;?i1;I7ZHbBN!5> z7|OmiKNMDJ{gHYpAxxftf<`lO+#rtWmGn}8uGcvl^SxOooHgB_I9Oro3wX#M#XL~) z&%ydP%#sc zZ2=*jsISu{C(^l62t97es|IvbEs4oN*qJfI2^l|+&e-?!6nET(pSjA!dNqIs`#+O! z(N*gXqlXFZyB-RXp`0|FqD+$K2WP8`Q$&}!{_eKLPeFjRd-AEKUtnzcLI|?mV4026 zMJ`n{^|tb_QwQ_TJu@v^n@}$df|X;4oSZ}m!x|_Xo6g%%5fPiK_E6XGQL?NJ)g{$JUR!r9W~G3Y?x%%&$P^LQ%6`Hl3OhbER;hujbsSUcW|( zNnZIoL1C*EdbJOnCA~|JIq@;{Uk6Zp%8ISEH{$Okiv{A@f60A6C7Q}+@OD?ZSi2PZ z{OYbt@3Vh-#U*3YouZh8tfq8xwTv$E6+qb>(r6ZHP)6dX5aAKrRsLIU+O64rI z#t$YKc^b^|nabl1x(2g&zyVynvA;E8=i$=bw@uxH zj5#79v8z!(U&JyWrntxvV_H-8%Xnssn3V$OVc4M2Ir%q-hKX8V-v?_t`8S^GLVT;d zUP9waXKI;+9dIHCVLw2Fll|HtzXSyAp~Es^Dj{wYw7%8l!A{^+aax!<*#^S`8~m2mwkgwho)cc6+}6Zhxq=t+gCT4yOh#7pO}5E zEIIrNq7Y#kkpMWW%`)r7+YL+kpm2lsCGpZ(3Fh&Q?{Oe$kO6-M?D~EmZFRw7{tBs# zPSvh)v+&D`qit)^(vd+1suDnJk=4Y_ZFjQ9p{XvOvdNB4;Wa-QcNiU4Fa%z^6bTr6 zB%gL{(zMJEj^UtP(0J$L7Rr;DFAc?|nVcbBIqd#Pf4-mUP&Y_A|y0r*X|2i?v z$zvwVPD_lr6XxxLk83G&F(E}P_35?qJLU26DtsoJk|E5!*3)_C;}nZWgwiBxdhL16 zdgatJ4rx=qXZTbwRZ}V1@N6>g1PQ-qVPv7$XdYS*aC{x&PxHPWNL+@V&&+Fm>J162 z6BdYBja`ebUU1gs)S%sI9aPHdQ!DUfrd=NkOByUGW|+U3<%aj<@3k7*y#%`Hy}hC{7hmOm=nG@bIiMrpU6#;*X9&mR5lttV8? z69>~LjVtl3>LuU@&ckVev^&jny0%Pe0H%n>oMnGNPu`{bZ-lP|QE1MGuYF*@75e&3 z@y@~E(zaaH(3Se;8u=vddfQJ!LIo?V)_vhl6M}Q&Ev_ycJpi3p%-Q^P?HjvCP3LD; z+!P0^_KkpH70Th^2G9e=NqwmO3%%736z?T0HrkK5oJpt(SgGa{A~*Itbl<9c?a`^3 zICL^NdFy@16K#c-HawMsGn$%O><3$=!Ua=+$$vSv-BqA=m7A8 zgDpu9s2i?+Do|r{kW*q8I{?*AO+h0^c>;h3Rqid!m$GzE?3F;IWDPZTrNHeIpUhFqRoE34r2Wafl@M{d6V??P*p0|&K4EB3rY^q4 z6`)MZSXc)k@I7oGQ#D@jH8fA8XD~8MlOWya$x*QX8o}Pnz#!yX;vZWE4vOWE;`Voh z9JRBsD&?z4&#}=;+}m63CG)lW;YwTzEH53Q*=FpdKeYXc{5|O98rvUgB0{A1{;bG! zihSi4{$O8F$^q(r|LCss+>ew@h=TeD$Y!^-SG>iPXil>UP#? z?y9DH}Li;*Y5WX&&tlQILPd;=siald6y@r^>Z zerzJcJCRTvQcDpnFIBY55#LDyOP$f;qp0jKd`_95!q}vF!h&Tb?$YIOI=b`#6`J-~2q^^R@Q z)7{pU-P3n~cnkTPxs?b0AQQJo<(gQDUVet$rSb&4W_Ckc8FjJf?D(&vB8IVRyxjs~ zIb7X=$FE&Pu(X2Df(F-0J)NwuozI55 z+KXuBRpc~paZu9@e%STQDPjPzP>F`$E&ihW;7IT+rPOZX^8loAIi&wrK<#pi9~LUi zteRWd)Koe@G?u^v$~$&?8MA9jnZ=iQCu)qrUeyhseTS5I)i$3nqQv;J;iX9iSrr8Z zJgjkE@|Rb zd_jvuLcWvvpi*I|{Z^h|48{1p6+5z5l}Pz2cN@Y8TQhIzenZ`H0M2hvdf%H#oBiC1 zhP)jGe#bdzj?y51pRb~72Yjkxli;q_NmdM2V$=F4N$FYk3PI>O%7L$$-4CNq?B!5; znmg#_?kR@u6&!Bh*r(38R;3cMeTZ;~x~F z#28O7xNkpoD1BUSMk)=i$86k6~qw9@)`)qA72@eC(txadOYA z%B(oez7BXxr}kSRF!G=`_a?gqd`#+_h_r%yy$G#{QeuRqP^BUr;6(~3-4*Yps#Jd=h26?#?@X1eD*!g|?RW`gLje!ta;BF< z9<~y~3R9ET!x8s=`{tqpMLccqQSm=n>h(9z#Vb`YY5vLzwhDg-^@bUHk6@0QnS}B# w@?gks7^;zO1IptV82|tP From 62b321ffa13d0b14e94c80119deaceddb55e7fea Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 4 Sep 2014 09:56:13 +1000 Subject: [PATCH 127/203] GPS shapes place holder removed from qrc --- ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc | 1 - 1 file changed, 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index 1eee82963..35a36a39d 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -46,6 +46,5 @@ resources/bttn-flash-up.png resources/bttn-upgrade-down.png resources/bttn-upgrade-up.png - resources/gps-shapes.svg From 91244cd47a77330ba42d03641e6e71e7ba88f5f3 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 4 Sep 2014 09:57:04 +1000 Subject: [PATCH 128/203] Airspeed shapes place holder gone --- ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc | 1 - 1 file changed, 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index 35a36a39d..897ff35e0 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -37,7 +37,6 @@ resources/multirotor-shapes.svg resources/fixedwing-shapes-wizard.svg resources/fixedwing-shapes-wizard-no-numbers.svg - resources/airspeed-shapes.svg resources/bttn-illustration-color-up.png resources/bttn-illustration-color-down.png resources/bttn-save-down.png From 7073b7c9fe180485fdec37b3fbe19797ba8697fc Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 4 Sep 2014 09:57:18 +1000 Subject: [PATCH 129/203] Remove actual file --- .../setupwizard/resources/airspeed-shapes.svg | 108 ------------------ 1 file changed, 108 deletions(-) delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/airspeed-shapes.svg diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/airspeed-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/airspeed-shapes.svg deleted file mode 100644 index 350e30e98..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/airspeed-shapes.svg +++ /dev/null @@ -1,108 +0,0 @@ - - - - - - - - - - image/svg+xml - - - - - - - OpenPilo - Eagletree - - - MS4525 - - - OpenPilot - - - From b57ea9cb6c5cac15e8a8c2d8f53f4b13b5d0303a Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 4 Sep 2014 09:58:50 +1000 Subject: [PATCH 130/203] Add new Sensor-shapes from Laurent --- ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc | 1 + 1 file changed, 1 insertion(+) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index 897ff35e0..c320a20e8 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -37,6 +37,7 @@ resources/multirotor-shapes.svg resources/fixedwing-shapes-wizard.svg resources/fixedwing-shapes-wizard-no-numbers.svg + resources/sensor-shapes.svg resources/bttn-illustration-color-up.png resources/bttn-illustration-color-down.png resources/bttn-save-down.png From c673bea4f030f93c7e6b19488a6f1b652bbc3408 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 4 Sep 2014 10:01:54 +1000 Subject: [PATCH 131/203] Start adding new sensor items, estimated --- .../openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index 5e7c90f62..4735ffd9e 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -53,7 +53,7 @@ void AirSpeedPage::setupSelection(Selection *selection) "to estimate wind speed and subtract it from ground speed obtained from the GPS.\n\n" "This solution is highly accurate in normal level flight with the drawback of being less " "accurate in rapid altitude changes.\n\n"), - "estimated", + "estimated-airspeed-sensor", SetupWizard::ESTIMATE); selection->addItem(tr("EagleTree"), From 99ec1c727e4af12972b03eeb9d871dc4b69a4e5e Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 4 Sep 2014 10:03:28 +1000 Subject: [PATCH 132/203] Aadd new sensor items, airspeed (EagleTree) --- .../openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index 4735ffd9e..b10f877a3 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -60,7 +60,7 @@ void AirSpeedPage::setupSelection(Selection *selection) tr("Select this option to use the Airspeed MicroSensor V3 from EagleTree, this is an accurate " "airspeed sensor that includes on-board Temperature Compensation.\n\n" "Selecting this option will set your board's Flexi-Port in to I2C mode."), - "eagletree", + "eagletree-speed-sensor", SetupWizard::EAGLETREE); selection->addItem(tr("MS4525 Based"), From 1b1c9938f32356ab8c305379154408b8e2788a52 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 4 Sep 2014 10:04:38 +1000 Subject: [PATCH 133/203] MS4525DO airspeed sensor support to wizard page --- .../openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index b10f877a3..5620a7ad0 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -67,6 +67,6 @@ void AirSpeedPage::setupSelection(Selection *selection) tr("Select this option to use an airspeed sensor based on the MS4525DO pressure transducer " "from Measurement Specialties. This includes the PixHawk sensor and their clones.\n\n" "Selecting this option will set your board's Flexi-Port in to I2C mode."), - "ms4525", + "ms4525-speed-sensor", SetupWizard::MS4525); } From 6635e5d9289e7b01d8f374132a2423859a637f28 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 4 Sep 2014 10:07:03 +1000 Subject: [PATCH 134/203] Update names in svg --- .../setupwizard/resources/sensor-shapes.svg | 204 +++++++++--------- 1 file changed, 104 insertions(+), 100 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg index 3ca39d3b3..56b254b81 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/sensor-shapes.svg @@ -1281,7 +1281,7 @@ inkscape:cx="-132.71044" inkscape:cy="583.5981" inkscape:document-units="px" - inkscape:current-layer="g14513" + inkscape:current-layer="layer1" showgrid="false" inkscape:snap-bbox="true" inkscape:object-paths="false" @@ -3467,111 +3467,115 @@ inkscape:label="No-GPS" style="display:inline" transform="translate(1.9073488e-7,3.930618e-6)"> - + id="no-gps" + inkscape:label="#g4506"> + style="opacity:0.46992481;fill:#2d2b2c;fill-opacity:1;stroke:#64676b;stroke-width:3.25399995;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" + d="m 90.193813,886.26947 262.075867,0 c 8.65078,0 15.61512,6.96434 15.61512,15.61511 l 0,262.07582 c 0,8.6508 -6.96434,15.6151 -15.61512,15.6151 l -262.075867,0 c -8.650773,0 -15.615113,-6.9643 -15.615113,-15.6151 l 0,-262.07582 c 0,-8.65077 6.96434,-15.61511 15.615113,-15.61511 z" + id="path13583" + inkscape:connector-curvature="0" /> + + + + + + + sodipodi:type="arc" + style="opacity:0.46992481;fill:url(#linearGradient13981);fill-opacity:1;fill-rule:evenodd;stroke:#515454;stroke-width:4.19999981;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" + id="path13631" + sodipodi:cx="-36.611858" + sodipodi:cy="572.3067" + sodipodi:rx="23.877298" + sodipodi:ry="23.877298" + d="m -12.73456,572.3067 a 23.877298,23.877298 0 1 1 -47.754597,0 23.877298,23.877298 0 1 1 47.754597,0 z" + transform="matrix(0.52050376,0,0,0.52050376,112.69192,607.43828)" /> + transform="matrix(0.52050376,0,0,0.52050376,112.69192,862.48512)" + d="m -12.73456,572.3067 a 23.877298,23.877298 0 1 1 -47.754597,0 23.877298,23.877298 0 1 1 47.754597,0 z" + sodipodi:ry="23.877298" + sodipodi:rx="23.877298" + sodipodi:cy="572.3067" + sodipodi:cx="-36.611858" + id="path13633" + style="opacity:0.46992481;fill:url(#linearGradient13983);fill-opacity:1;fill-rule:evenodd;stroke:#515454;stroke-width:4.19999981;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" + sodipodi:type="arc" /> - - - - - - + + NO GPS - - + y="899.23615" + id="text13921" + sodipodi:linespacing="125%" + transform="matrix(0.70710678,-0.70710678,0.70710678,0.70710678,0,0)" + inkscape:transform-center-x="31.310554" + inkscape:transform-center-y="225.64679">NO GPS + + + Date: Thu, 4 Sep 2014 10:40:08 +1000 Subject: [PATCH 135/203] Add selected GPS type to summary --- .../src/plugins/setupwizard/setupwizard.cpp | 19 +++++++++++++++++++ 1 file changed, 19 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index a08c71040..3de584d74 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -356,6 +356,7 @@ QString SetupWizard::getSummaryText() summary.append(tr("Unknown")); } + // If Tricopter show tail servo speed if (getVehicleSubType() == MULTI_ROTOR_TRI_Y || getVehicleType() == VEHICLE_FIXEDWING) { summary.append("
"); summary.append("").append(tr("Servo type: ")).append(""); @@ -371,6 +372,24 @@ QString SetupWizard::getSummaryText() } } + // Show GPS Type + if (getControllerType() == CONTROLLER_REVO || getControllerType() == CONTROLLER_NANO) { + summary.append("
"); + summary.append("").append(tr("GPS type: ")).append(""); + switch (getGpsType()) { + case GPS_PLAT: + summary.append(tr("OpenPilot Platinum")); + break; + case GPS_UBX: + summary.append(tr("OpenPilot v8 or Generic UBLOX GPS")); + break; + case GPS_NMEA: + summary.append(tr("Generic NMEA GPS")); + break; + default: + summary.append(tr("None")); + } + } /* summary.append("
"); summary.append("").append(tr("Reboot required: ")).append(""); From 135853d5a155799b975da0c4a06013ac0224d939 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Thu, 4 Sep 2014 10:59:11 +1000 Subject: [PATCH 136/203] Add airspeed type selction to summary --- .../src/plugins/setupwizard/setupwizard.cpp | 20 +++++++++++++++++++ 1 file changed, 20 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 3de584d74..92a157a63 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -390,6 +390,26 @@ QString SetupWizard::getSummaryText() summary.append(tr("None")); } } + + // Show Airspeed sensor type + if ((getControllerType() == CONTROLLER_REVO || getControllerType() == CONTROLLER_NANO) && getVehicleType() == VEHICLE_FIXEDWING) { + summary.append("
"); + summary.append("").append(tr("Airspeed Sensor: ")).append(""); + switch (getAirspeedType()) { + case ESTIMATE: + summary.append(tr("Software Estimated")); + break; + case EAGLETREE: + summary.append(tr("EagleTree on Flexi-Port")); + break; + case MS4525: + summary.append(tr("MS4525 based on Flexi-Port")); + break; + default: + summary.append(tr("Unknown")); + } + } + /* summary.append("
"); summary.append("").append(tr("Reboot required: ")).append(""); From b1a7f959b5c455a32bbd70883f6d2194652b803b Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Fri, 5 Sep 2014 17:14:27 +1000 Subject: [PATCH 137/203] Initial tuning page --- ...page.cpp => airframeinitialtuningpage.cpp} | 10 +-- ...wingpage.h => airframeinitialtuningpage.h} | 16 ++-- .../pages/airframeinitialtuningpage.ui | 87 +++++++++++++++++++ .../pages/airframestabfixedwingpage.ui | 45 ---------- .../src/plugins/setupwizard/setupwizard.cpp | 8 +- .../src/plugins/setupwizard/setupwizard.h | 2 +- .../src/plugins/setupwizard/setupwizard.pro | 12 +-- 7 files changed, 111 insertions(+), 69 deletions(-) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{airframestabfixedwingpage.cpp => airframeinitialtuningpage.cpp} (83%) rename ground/openpilotgcs/src/plugins/setupwizard/pages/{airframestabfixedwingpage.h => airframeinitialtuningpage.h} (77%) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.ui delete mode 100644 ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.ui diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp similarity index 83% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.cpp rename to ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp index 431e84f40..9983abf76 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp @@ -25,17 +25,17 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#include "airframestabfixedwingpage.h" -#include "ui_airframestabfixedwingpage.h" +#include "airframeinitialtuningpage.h" +#include "ui_airframeinitialtuningpage.h" -AirframeStabFixedwingPage::AirframeStabFixedwingPage(SetupWizard *wizard, QWidget *parent) : +AirframeInitialTuningPage::AirframeInitialTuningPage(SetupWizard *wizard, QWidget *parent) : AbstractWizardPage(wizard, parent), - ui(new Ui::AirframeStabFixedwingPage) + ui(new Ui::AirframeInitialTuningPage) { ui->setupUi(this); } -AirframeStabFixedwingPage::~AirframeStabFixedwingPage() +AirframeInitialTuningPage::~AirframeInitialTuningPage() { delete ui; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.h similarity index 77% rename from ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.h rename to ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.h index 4a6dae8dc..fe92e1ee6 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.h @@ -25,24 +25,24 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -#ifndef AIRFRAMESTABFIXEDWINGPAGE_H -#define AIRFRAMESTABFIXEDWINGPAGE_H +#ifndef AIRFRAMEINITIALTUNINGPAGE_H +#define AIRFRAMEINITIALTUNINGPAGE_H #include "abstractwizardpage.h" namespace Ui { -class AirframeStabFixedwingPage; +class AirframeInitialTuningPage; } -class AirframeStabFixedwingPage : public AbstractWizardPage { +class AirframeInitialTuningPage : public AbstractWizardPage { Q_OBJECT public: - explicit AirframeStabFixedwingPage(SetupWizard *wizard, QWidget *parent = 0); - ~AirframeStabFixedwingPage(); + explicit AirframeInitialTuningPage(SetupWizard *wizard, QWidget *parent = 0); + ~AirframeInitialTuningPage(); private: - Ui::AirframeStabFixedwingPage *ui; + Ui::AirframeInitialTuningPage *ui; }; -#endif // AIRFRAMESTABFIXEDWINGPAGE_H +#endif // AIRFRAMEINITIALTUNINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.ui new file mode 100644 index 000000000..6a87e690a --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.ui @@ -0,0 +1,87 @@ + + + AirframeInitialTuningPage + + + + 0 + 0 + 600 + 400 + + + + WizardPage + + + + + 9 + 9 + 582 + 81 + + + + <!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:12pt; font-weight:600;">Initial Tuning</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-family:'MS Shell Dlg 2,sans-serif';">This section of the OpenPilot Wizard allows you to select a set of initial tunning parameters for your airframe. Presented below is a list of common airframe types, select the one that matches your airframe the closest, if unsure select the generic variant.</span> </p></body></html> + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + + + + + 10 + 100 + 581 + 291 + + + + + + + + + Qt::ScrollBarAlwaysOn + + + + + + + + + + + + Description + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + + + + + + + + label_main + label_main + horizontalLayoutWidget + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.ui deleted file mode 100644 index 31e672b1f..000000000 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframestabfixedwingpage.ui +++ /dev/null @@ -1,45 +0,0 @@ - - - AirframeStabFixedwingPage - - - - 0 - 0 - 600 - 400 - - - - WizardPage - - - - - 20 - 130 - 551 - 191 - - - - <!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;">TODO: This page handles PIDs, we get a choice of airframes, some generics as well as specifics like FPV Raptor and Funjet etc</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:12pt; font-weight:600;">Explain these are a starting point and likely will need further tuning as no two airframes are completely identical </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></body></html> - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 92a157a63..25e3ad1b2 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -46,7 +46,7 @@ #include "pages/rebootpage.h" #include "pages/outputcalibrationpage.h" #include "pages/revocalibrationpage.h" -#include "pages/airframestabfixedwingpage.h" +#include "pages/airframeinitialtuningpage.h" #include "extensionsystem/pluginmanager.h" #include "vehicleconfigurationhelper.h" #include "actuatorsettings.h" @@ -163,7 +163,7 @@ int SetupWizard::nextId() const { switch (getVehicleType()) { case VEHICLE_FIXEDWING: - return PAGE_AIRFRAMESTAB_FIXEDWING; + return PAGE_AIRFRAME_INITIAL_TUNING; // TODO: PID selection pages for multi and heli case VEHICLE_MULTI: @@ -186,7 +186,7 @@ int SetupWizard::nextId() const case PAGE_AIRSPEED: return PAGE_SUMMARY; - case PAGE_AIRFRAMESTAB_FIXEDWING: + case PAGE_AIRFRAME_INITIAL_TUNING: return PAGE_SAVE; case PAGE_SUMMARY: @@ -440,7 +440,7 @@ void SetupWizard::createPages() setPage(PAGE_SAVE, new SavePage(this)); setPage(PAGE_REBOOT, new RebootPage(this)); setPage(PAGE_NOTYETIMPLEMENTED, new NotYetImplementedPage(this)); - setPage(PAGE_AIRFRAMESTAB_FIXEDWING, new AirframeStabFixedwingPage(this)); + setPage(PAGE_AIRFRAME_INITIAL_TUNING, new AirframeInitialTuningPage(this)); setPage(PAGE_END, new OPEndPage(this)); setStartId(PAGE_START); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h index 8fb9fd325..f46163792 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -177,7 +177,7 @@ private: enum { PAGE_START, PAGE_CONTROLLER, PAGE_VEHICLES, PAGE_MULTI, PAGE_FIXEDWING, PAGE_AIRSPEED, PAGE_GPS, PAGE_HELI, PAGE_SURFACE, PAGE_INPUT, PAGE_ESC, PAGE_SERVO, PAGE_BIAS_CALIBRATION, PAGE_REVO_CALIBRATION, PAGE_OUTPUT_CALIBRATION, - PAGE_SAVE, PAGE_SUMMARY, PAGE_NOTYETIMPLEMENTED, PAGE_AIRFRAMESTAB_FIXEDWING, + PAGE_SAVE, PAGE_SUMMARY, PAGE_NOTYETIMPLEMENTED, PAGE_AIRFRAME_INITIAL_TUNING, PAGE_REBOOT, PAGE_END, PAGE_UPDATE }; void createPages(); bool saveHardwareSettings() const; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index eec6f4e69..b9e651d3e 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -37,10 +37,10 @@ HEADERS += setupwizardplugin.h \ pages/revocalibrationpage.h \ biascalibrationutil.h \ pages/biascalibrationpage.h \ - pages/airframestabfixedwingpage.h \ pages/escpage.h \ pages/servopage.h \ - pages/selectionpage.h + pages/selectionpage.h \ + pages/airframeinitialtuningpage.h SOURCES += setupwizardplugin.cpp \ setupwizard.cpp \ @@ -69,10 +69,10 @@ SOURCES += setupwizardplugin.cpp \ pages/revocalibrationpage.cpp \ biascalibrationutil.cpp \ pages/biascalibrationpage.cpp \ - pages/airframestabfixedwingpage.cpp \ pages/escpage.cpp \ pages/servopage.cpp \ - pages/selectionpage.cpp + pages/selectionpage.cpp \ + pages/airframeinitialtuningpage.cpp OTHER_FILES += SetupWizard.pluginspec @@ -93,10 +93,10 @@ FORMS += \ pages/autoupdatepage.ui \ pages/revocalibrationpage.ui \ pages/biascalibrationpage.ui \ - pages/airframestabfixedwingpage.ui \ pages/escpage.ui \ pages/servopage.ui \ - pages/selectionpage.ui + pages/selectionpage.ui \ + pages/airframeinitialtuningpage.ui RESOURCES += \ wizardResources.qrc From ce64aa2ca7b4a3abf9e27b735902786cd7b6a5c1 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Fri, 5 Sep 2014 17:21:37 +1000 Subject: [PATCH 138/203] Add for other airframe types --- .../src/plugins/setupwizard/setupwizard.cpp | 19 +++---------------- 1 file changed, 3 insertions(+), 16 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 25e3ad1b2..61e18e7e1 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -160,20 +160,10 @@ int SetupWizard::nextId() const // case PAGE_REVO_CALIBRATION: // return PAGE_OUTPUT_CALIBRATION; case PAGE_OUTPUT_CALIBRATION: - { - switch (getVehicleType()) { - case VEHICLE_FIXEDWING: - return PAGE_AIRFRAME_INITIAL_TUNING; - - // TODO: PID selection pages for multi and heli - case VEHICLE_MULTI: - case VEHICLE_HELI: - case VEHICLE_SURFACE: - case VEHICLE_UNKNOWN: - return PAGE_SAVE; - } - } + return PAGE_AIRFRAME_INITIAL_TUNING; + case PAGE_AIRFRAME_INITIAL_TUNING: + return PAGE_SAVE; case PAGE_GPS: switch (getVehicleType()) { @@ -186,9 +176,6 @@ int SetupWizard::nextId() const case PAGE_AIRSPEED: return PAGE_SUMMARY; - case PAGE_AIRFRAME_INITIAL_TUNING: - return PAGE_SAVE; - case PAGE_SUMMARY: { switch (getControllerType()) { From cefffefd7bdd336a5c6a4963847cd655030f3cd1 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Fri, 5 Sep 2014 17:22:59 +1000 Subject: [PATCH 139/203] Uncrustify --- .../src/plugins/setupwizard/pages/gpspage.cpp | 1 - .../src/plugins/setupwizard/setupwizard.cpp | 62 ++++++++++--------- .../setupwizard/vehicleconfigurationsource.h | 6 +- 3 files changed, 36 insertions(+), 33 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp index 6d53cbda6..5f02fca6d 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp @@ -73,5 +73,4 @@ void GpsPage::setupSelection(Selection *selection) "controller."), "generic-nmea", SetupWizard::GPS_NMEA); - } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 61e18e7e1..5a2d7c6c5 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -138,10 +138,11 @@ int SetupWizard::nextId() const case CONTROLLER_REVO: case CONTROLLER_NANO: return PAGE_GPS; + default: return PAGE_SUMMARY; - } - } + } + } case PAGE_SERVO: { @@ -149,9 +150,10 @@ int SetupWizard::nextId() const case CONTROLLER_REVO: case CONTROLLER_NANO: return PAGE_GPS; + default: return PAGE_SUMMARY; - } + } } case PAGE_BIAS_CALIBRATION: @@ -169,9 +171,10 @@ int SetupWizard::nextId() const switch (getVehicleType()) { case VEHICLE_FIXEDWING: return PAGE_AIRSPEED; + default: return PAGE_SUMMARY; - } + } case PAGE_AIRSPEED: return PAGE_SUMMARY; @@ -183,8 +186,9 @@ int SetupWizard::nextId() const case CONTROLLER_CC3D: case CONTROLLER_REVO: switch (getVehicleType()) { - case VEHICLE_FIXEDWING: + case VEHICLE_FIXEDWING: return PAGE_OUTPUT_CALIBRATION; + default: return PAGE_BIAS_CALIBRATION; } @@ -364,18 +368,18 @@ QString SetupWizard::getSummaryText() summary.append("
"); summary.append("").append(tr("GPS type: ")).append(""); switch (getGpsType()) { - case GPS_PLAT: - summary.append(tr("OpenPilot Platinum")); - break; - case GPS_UBX: - summary.append(tr("OpenPilot v8 or Generic UBLOX GPS")); - break; - case GPS_NMEA: - summary.append(tr("Generic NMEA GPS")); - break; - default: - summary.append(tr("None")); - } + case GPS_PLAT: + summary.append(tr("OpenPilot Platinum")); + break; + case GPS_UBX: + summary.append(tr("OpenPilot v8 or Generic UBLOX GPS")); + break; + case GPS_NMEA: + summary.append(tr("Generic NMEA GPS")); + break; + default: + summary.append(tr("None")); + } } // Show Airspeed sensor type @@ -383,18 +387,18 @@ QString SetupWizard::getSummaryText() summary.append("
"); summary.append("").append(tr("Airspeed Sensor: ")).append(""); switch (getAirspeedType()) { - case ESTIMATE: - summary.append(tr("Software Estimated")); - break; - case EAGLETREE: - summary.append(tr("EagleTree on Flexi-Port")); - break; - case MS4525: - summary.append(tr("MS4525 based on Flexi-Port")); - break; - default: - summary.append(tr("Unknown")); - } + case ESTIMATE: + summary.append(tr("Software Estimated")); + break; + case EAGLETREE: + summary.append(tr("EagleTree on Flexi-Port")); + break; + case MS4525: + summary.append(tr("MS4525 based on Flexi-Port")); + break; + default: + summary.append(tr("Unknown")); + } } /* diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 7b7f66b0a..635a35730 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -71,9 +71,9 @@ public: virtual VehicleConfigurationSource::CONTROLLER_TYPE getControllerType() const = 0; virtual VehicleConfigurationSource::VEHICLE_TYPE getVehicleType() const = 0; virtual VehicleConfigurationSource::VEHICLE_SUB_TYPE getVehicleSubType() const = 0; - virtual VehicleConfigurationSource::INPUT_TYPE getInputType() const = 0; - virtual VehicleConfigurationSource::ESC_TYPE getEscType() const = 0; - virtual VehicleConfigurationSource::SERVO_TYPE getServoType() const = 0; + virtual VehicleConfigurationSource::INPUT_TYPE getInputType() const = 0; + virtual VehicleConfigurationSource::ESC_TYPE getEscType() const = 0; + virtual VehicleConfigurationSource::SERVO_TYPE getServoType() const = 0; virtual VehicleConfigurationSource::AIRSPEED_TYPE getAirspeedType() const = 0; virtual VehicleConfigurationSource::GPS_TYPE getGpsType() const = 0; virtual VehicleConfigurationSource::RADIO_SETTING getRadioSetting() const = 0; From 1d50f9e949c224f63516354fc9d6d1e05cb13a77 Mon Sep 17 00:00:00 2001 From: m_thread Date: Fri, 5 Sep 2014 17:30:20 +0200 Subject: [PATCH 140/203] OP-1222 Added support for gps and airspeedsensors in connection diagram. Optimized bounding rect handling. Got rid of need for background element. --- .../plugins/setupwizard/connectiondiagram.cpp | 83 ++++++++++++++----- .../plugins/setupwizard/connectiondiagram.h | 2 +- 2 files changed, 62 insertions(+), 23 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp index adfe9002c..0618e01ac 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -31,8 +31,10 @@ #include "connectiondiagram.h" #include "ui_connectiondiagram.h" +const char* ConnectionDiagram::FILE_NAME = ":/setupwizard/resources/connection-diagrams.svg"; + ConnectionDiagram::ConnectionDiagram(QWidget *parent, VehicleConfigurationSource *configSource) : - QDialog(parent), ui(new Ui::ConnectionDiagram), m_configSource(configSource), m_background(0) + QDialog(parent), ui(new Ui::ConnectionDiagram), m_configSource(configSource) { ui->setupUi(this); setWindowTitle(tr("Connection Diagram")); @@ -48,33 +50,24 @@ void ConnectionDiagram::resizeEvent(QResizeEvent *event) { QWidget::resizeEvent(event); - ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio); + ui->connectionDiagram->fitInView(m_scene->itemsBoundingRect(), Qt::KeepAspectRatio); } void ConnectionDiagram::showEvent(QShowEvent *event) { QWidget::showEvent(event); - ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio); + ui->connectionDiagram->fitInView(m_scene->itemsBoundingRect(), 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")) && + if (QFile::exists(QString(FILE_NAME)) && + m_renderer->load(QString(FILE_NAME)) && 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 elementsToShow; @@ -178,10 +171,62 @@ void ConnectionDiagram::setupGraphicsScene() break; } + switch (m_configSource->getGpsType()) { + case VehicleConfigurationSource::GPS_DISABLED: + break; + case VehicleConfigurationSource::GPS_NMEA: + if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { + elementsToShow << "nano-generic-nmea"; + } else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) { + elementsToShow << "generic-nmea"; + } + break; + case VehicleConfigurationSource::GPS_PLATINUM: + if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { + elementsToShow << "nano-OPGPS-v9"; + } else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) { + elementsToShow << "OPGPS-v9"; + } + break; + case VehicleConfigurationSource::GPS_UBX: + if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { + elementsToShow << "nano-OPGPS-v8-ublox"; + } else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) { + elementsToShow << "OPGPS-v8-ublox"; + } + break; + default: + break; + } + + if (m_configSource->getVehicleType() == VehicleConfigurationSource::VEHICLE_FIXEDWING && + m_configSource->getAirspeedType() != VehicleConfigurationSource::AIRSPEED_ESTIMATE) { + switch (m_configSource->getAirspeedType()) { + case VehicleConfigurationSource::AIRSPEED_EAGLETREE: + if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { + elementsToShow << "nano-eagletree-speed-sensor"; + } else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) { + elementsToShow << "eagletree-speed-sensor"; + } + break; + case VehicleConfigurationSource::AIRSPEED_MS4525: + if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { + elementsToShow << "nano-ms4525-speed-sensor"; + } else if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_REVO) { + elementsToShow << "ms4525-speed-sensor"; + } + break; + default: + break; + } + } + setupGraphicsSceneItems(elementsToShow); - ui->connectionDiagram->setSceneRect(m_background->boundingRect()); - ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio); + ui->connectionDiagram->setSceneRect(m_scene->itemsBoundingRect()); + //ui->connectionDiagram->setSceneRect(m_background); + ui->connectionDiagram->fitInView(m_scene->itemsBoundingRect(), Qt::KeepAspectRatio); + //ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio); qDebug() << "Scene complete"; } @@ -191,8 +236,6 @@ void ConnectionDiagram::setupGraphicsSceneItems(QList elementsToShow) { qreal z = 0; - // QRectF backgBounds = m_renderer->boundsOnElement("background"); - foreach(QString elementId, elementsToShow) { if (m_renderer->elementExists(elementId)) { QGraphicsSvgItem *element = new QGraphicsSvgItem(); @@ -204,10 +247,6 @@ void ConnectionDiagram::setupGraphicsSceneItems(QList elementsToShow) 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 { diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.h b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.h index 8d7a0574d..5e4162a42 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.h @@ -48,11 +48,11 @@ public: ~ConnectionDiagram(); private: + static const char *FILE_NAME; Ui::ConnectionDiagram *ui; VehicleConfigurationSource *m_configSource; QSvgRenderer *m_renderer; - QGraphicsSvgItem *m_background; QGraphicsScene *m_scene; void setupGraphicsScene(); From 73d1217cc736e98ac68c5bfe4f96620b13423274 Mon Sep 17 00:00:00 2001 From: m_thread Date: Fri, 5 Sep 2014 17:31:41 +0200 Subject: [PATCH 141/203] OP-1222 Added code to handle port conflicts in configuration. --- .../setupwizard/pages/airspeedpage.cpp | 25 +++++++++++++--- .../plugins/setupwizard/pages/airspeedpage.h | 4 ++- .../setupwizard/pages/fixedwingpage.cpp | 5 ++++ .../plugins/setupwizard/pages/fixedwingpage.h | 3 +- .../src/plugins/setupwizard/pages/gpspage.cpp | 7 ++++- .../src/plugins/setupwizard/pages/gpspage.h | 1 + .../plugins/setupwizard/pages/multipage.cpp | 5 ++++ .../src/plugins/setupwizard/pages/multipage.h | 3 +- .../setupwizard/pages/selectionpage.cpp | 19 +++++++++--- .../plugins/setupwizard/pages/selectionpage.h | 22 +++++++++----- .../plugins/setupwizard/pages/summarypage.ui | 21 +++++++------ .../src/plugins/setupwizard/setupwizard.cpp | 30 +++++++++---------- .../vehicleconfigurationhelper.cpp | 1 + .../setupwizard/vehicleconfigurationsource.h | 4 +-- 14 files changed, 102 insertions(+), 48 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index 5620a7ad0..27a9d4a07 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -35,6 +35,20 @@ AirSpeedPage::AirSpeedPage(SetupWizard *wizard, QWidget *parent) : AirSpeedPage::~AirSpeedPage() {} +void AirSpeedPage::initializePage(VehicleConfigurationSource *settings) +{ + // Enable all + setItemDisabled(-1, false); + if (settings->getInputType() == VehicleConfigurationSource::INPUT_SBUS || + settings->getInputType() == VehicleConfigurationSource::INPUT_DSM2 || + settings->getInputType() == VehicleConfigurationSource::INPUT_DSMX10 || + settings->getInputType() == VehicleConfigurationSource::INPUT_DSMX11) { + // Disable non estimated sensors if ports are taken by receivers + setItemDisabled(VehicleConfigurationSource::AIRSPEED_EAGLETREE, true); + setItemDisabled(VehicleConfigurationSource::AIRSPEED_MS4525, true); + } +} + bool AirSpeedPage::validatePage(SelectionItem *selectedItem) { getWizard()->setAirspeedType((SetupWizard::AIRSPEED_TYPE)selectedItem->id()); @@ -46,7 +60,9 @@ void AirSpeedPage::setupSelection(Selection *selection) selection->setTitle(tr("OpenPilot Airspeed Sensor Selection")); selection->setText(tr("This part of the wizard will help you select and configure a way to obtain " "airspeed data. OpenPilot support three methods to achieve this, one is a " - "software estimation technique and the other two utilize hardware sensors.\n\n" + "software estimation technique and the other two utilize hardware sensors.\n" + "Note: if previously selected input combinations use the Flexi-port for input, " + "only estimated airspeed will be avilible.\n\n" "Please select how you wish to obtain airspeed data below:")); selection->addItem(tr("Estimated"), tr("This option uses an intelligent estimation algorithm which utilizes the OpenPilot INS/GPS " @@ -54,19 +70,20 @@ void AirSpeedPage::setupSelection(Selection *selection) "This solution is highly accurate in normal level flight with the drawback of being less " "accurate in rapid altitude changes.\n\n"), "estimated-airspeed-sensor", - SetupWizard::ESTIMATE); + SetupWizard::AIRSPEED_ESTIMATE); selection->addItem(tr("EagleTree"), tr("Select this option to use the Airspeed MicroSensor V3 from EagleTree, this is an accurate " "airspeed sensor that includes on-board Temperature Compensation.\n\n" "Selecting this option will set your board's Flexi-Port in to I2C mode."), "eagletree-speed-sensor", - SetupWizard::EAGLETREE); + SetupWizard::AIRSPEED_EAGLETREE); selection->addItem(tr("MS4525 Based"), tr("Select this option to use an airspeed sensor based on the MS4525DO pressure transducer " "from Measurement Specialties. This includes the PixHawk sensor and their clones.\n\n" "Selecting this option will set your board's Flexi-Port in to I2C mode."), "ms4525-speed-sensor", - SetupWizard::MS4525); + SetupWizard::AIRSPEED_MS4525); } + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h index 6affa4458..e87838f7a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h @@ -37,9 +37,11 @@ public: explicit AirSpeedPage(SetupWizard *wizard, QWidget *parent = 0); ~AirSpeedPage(); -public: +protected: + void initializePage(VehicleConfigurationSource *settings); bool validatePage(SelectionItem *selectedItem); void setupSelection(Selection *selection); + }; #endif // AIRSPEEDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp index baa255014..dfc2a9ca2 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.cpp @@ -35,6 +35,11 @@ FixedWingPage::FixedWingPage(SetupWizard *wizard, QWidget *parent) : FixedWingPage::~FixedWingPage() {} +void FixedWingPage::initializePage(VehicleConfigurationSource *settings) +{ + Q_UNUSED(settings); +} + bool FixedWingPage::validatePage(SelectionItem *selectedItem) { getWizard()->setVehicleSubType((SetupWizard::VEHICLE_SUB_TYPE)selectedItem->id()); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h index e2e696eeb..af0a04980 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/fixedwingpage.h @@ -37,7 +37,8 @@ public: explicit FixedWingPage(SetupWizard *wizard, QWidget *parent = 0); ~FixedWingPage(); -public: +protected: + void initializePage(VehicleConfigurationSource *settings); bool validatePage(SelectionItem *selectedItem); void setupSelection(Selection *selection); }; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp index 5f02fca6d..e8ed72aaa 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp @@ -35,6 +35,11 @@ GpsPage::GpsPage(SetupWizard *wizard, QWidget *parent) : GpsPage::~GpsPage() {} +void GpsPage::initializePage(VehicleConfigurationSource *settings) +{ + Q_UNUSED(settings); +} + bool GpsPage::validatePage(SelectionItem *selectedItem) { getWizard()->setGpsType((SetupWizard::GPS_TYPE)selectedItem->id()); @@ -60,7 +65,7 @@ void GpsPage::setupSelection(Selection *selection) "and Microcontroller connected to the Main Port of your controller.\n\n" "Note: for the OpenPilot v8 GPS please select the U-Blox option."), "OPGPS-v9", - SetupWizard::GPS_PLAT); + SetupWizard::GPS_PLATINUM); selection->addItem(tr("U-Blox Based"), tr("Select this option for the OpenPilot V8 GPS or generic U-Blox chipset GPSs connected" diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h index c53df8f17..84b754aad 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.h @@ -38,6 +38,7 @@ public: ~GpsPage(); public: + void initializePage(VehicleConfigurationSource *settings); bool validatePage(SelectionItem *selectedItem); void setupSelection(Selection *selection); }; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp index 96ab087f6..014968850 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp @@ -35,6 +35,11 @@ MultiPage::MultiPage(SetupWizard *wizard, QWidget *parent) : MultiPage::~MultiPage() {} +void MultiPage::initializePage(VehicleConfigurationSource *settings) +{ + Q_UNUSED(settings); +} + bool MultiPage::validatePage(SelectionItem *selectedItem) { getWizard()->setVehicleSubType((SetupWizard::VEHICLE_SUB_TYPE)selectedItem->id()); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h index 20cc10fd6..103258dbe 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h @@ -37,7 +37,8 @@ public: explicit MultiPage(SetupWizard *wizard, QWidget *parent = 0); virtual ~MultiPage(); -public: +protected: + void initializePage(VehicleConfigurationSource *settings); bool validatePage(SelectionItem *selectedItem); void setupSelection(Selection *selection); }; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp index a00275244..363a8f80e 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp @@ -68,6 +68,7 @@ void SelectionPage::initializePage() ui->typeCombo->setCurrentIndex(0); } } + initializePage(getWizard()); } bool SelectionPage::validatePage() @@ -104,9 +105,9 @@ void SelectionPage::selectionChanged(int index) fitImage(); } -void SelectionPage::addItem(QString name, QString description, QString shapeId, int id) +void SelectionPage::addItem(QString name, QString description, QString shapeId, int id, bool disabled) { - m_selectionItems << new SelectionItem(name, description, shapeId, id); + m_selectionItems << new SelectionItem(name, description, shapeId, id, disabled); } void SelectionPage::setTitle(QString title) @@ -119,6 +120,16 @@ void SelectionPage::setText(QString text) ui->text->setText(text); } -SelectionItem::SelectionItem(QString name, QString description, QString shapeId, int id) : - m_name(name), m_description(description), m_shapeId(shapeId), m_id(id) +void SelectionPage::setItemDisabled(int id, bool disabled) +{ + for (int i = 0; i < m_selectionItems.count(); i++) { + if (id < 0 || m_selectionItems.at(i)->id() == id) { + m_selectionItems.at(i)->setDisabled(disabled); + ui->typeCombo->setItemData(i, disabled ? 0 : 33, Qt::UserRole - 1); + } + } +} + +SelectionItem::SelectionItem(QString name, QString description, QString shapeId, int id, bool disabled) : + m_name(name), m_description(description), m_shapeId(shapeId), m_id(id), m_disabled(disabled) {} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h index 039a639f9..5802f5fd5 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h @@ -40,8 +40,7 @@ class SelectionPage; class SelectionItem { public: - SelectionItem(QString name, QString description, QString shapeId, int id); -// ~SelectionItem(); + SelectionItem(QString name, QString description, QString shapeId, int id, bool disabled = false); QString name() { @@ -59,20 +58,28 @@ public: { return m_id; } + void setDisabled(bool disabled) { + m_disabled = disabled; + } + bool disabled() { + return m_disabled; + } private: QString m_name; QString m_description; QString m_shapeId; int m_id; + bool m_disabled; }; class Selection { public: Selection() {} - virtual void addItem(QString name, QString description, QString shapeId, int id) = 0; + virtual void addItem(QString name, QString description, QString shapeId, int id, bool disabled = false) = 0; virtual void setTitle(QString title) = 0; virtual void setText(QString text) = 0; + virtual void setItemDisabled(int id, bool disabled) = 0; }; class SelectionPage : public AbstractWizardPage, public Selection { @@ -84,14 +91,15 @@ public: void initializePage(); bool validatePage(); - void addItem(QString name, QString description, QString shapeId, int id); + void addItem(QString name, QString description, QString shapeId, int id, bool disabled = false); void setTitle(QString title); void setText(QString text); - - virtual void setupSelection(Selection *selection) = 0; - virtual bool validatePage(SelectionItem *selectedItem) = 0; + void setItemDisabled(int id, bool disabled); protected: + virtual void setupSelection(Selection *selection) = 0; + virtual void initializePage(VehicleConfigurationSource *settings) = 0; + virtual bool validatePage(SelectionItem *selectedItem) = 0; void resizeEvent(QResizeEvent *event); void showEvent(QShowEvent *event); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui index 716956709..f318aafe3 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui @@ -20,15 +20,14 @@ <!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: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> +</style></head><body style=" font-family:'Ubuntu'; font-size:11pt; 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-family:'MS Shell Dlg 2'; 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-family:'MS Shell Dlg 2'; 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-family:'MS Shell Dlg 2'; 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-family:'MS Shell Dlg 2'; 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-family:'MS Shell Dlg 2'; 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:'MS Shell Dlg 2'; 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=" 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 following steps require that your OpenPilot controller is set up according to the diagram, it is </span><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt; font-weight:600;">connected to the computer</span><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;"> by USB, and that the vehicle is</span><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt; font-weight:600;"> powered by a battery</span><span style=" font-family:'MS Shell Dlg 2'; font-size:10pt;">.</span></p></body></html> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop @@ -78,8 +77,8 @@ p, li { white-space: pre-wrap; } - 150 - 150 + 120 + 120 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 5a2d7c6c5..22ec8bbf4 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -88,6 +88,7 @@ int SetupWizard::nextId() const case CONTROLLER_CC: case CONTROLLER_CC3D: case CONTROLLER_REVO: + case CONTROLLER_NANO: return PAGE_INPUT; case CONTROLLER_OPLINK: @@ -159,8 +160,6 @@ int SetupWizard::nextId() const case PAGE_BIAS_CALIBRATION: return PAGE_OUTPUT_CALIBRATION; - // case PAGE_REVO_CALIBRATION: - // return PAGE_OUTPUT_CALIBRATION; case PAGE_OUTPUT_CALIBRATION: return PAGE_AIRFRAME_INITIAL_TUNING; @@ -170,8 +169,11 @@ int SetupWizard::nextId() const case PAGE_GPS: switch (getVehicleType()) { case VEHICLE_FIXEDWING: - return PAGE_AIRSPEED; - + if (getGpsType() != GPS_DISABLED) { + return PAGE_AIRSPEED; + } else { + return PAGE_SUMMARY; + } default: return PAGE_SUMMARY; } @@ -185,10 +187,10 @@ int SetupWizard::nextId() const case CONTROLLER_CC: case CONTROLLER_CC3D: case CONTROLLER_REVO: + case CONTROLLER_NANO: switch (getVehicleType()) { case VEHICLE_FIXEDWING: return PAGE_OUTPUT_CALIBRATION; - default: return PAGE_BIAS_CALIBRATION; } @@ -222,6 +224,9 @@ QString SetupWizard::getSummaryText() case CONTROLLER_REVO: summary.append(tr("OpenPilot Revolution")); break; + case CONTROLLER_NANO: + summary.append(tr("OpenPilot Nano")); + break; case CONTROLLER_OPLINK: summary.append(tr("OpenPilot OPLink Radio Modem")); break; @@ -368,7 +373,7 @@ QString SetupWizard::getSummaryText() summary.append("
"); summary.append("").append(tr("GPS type: ")).append(""); switch (getGpsType()) { - case GPS_PLAT: + case GPS_PLATINUM: summary.append(tr("OpenPilot Platinum")); break; case GPS_UBX: @@ -387,25 +392,19 @@ QString SetupWizard::getSummaryText() summary.append("
"); summary.append("").append(tr("Airspeed Sensor: ")).append(""); switch (getAirspeedType()) { - case ESTIMATE: + case AIRSPEED_ESTIMATE: summary.append(tr("Software Estimated")); break; - case EAGLETREE: + case AIRSPEED_EAGLETREE: summary.append(tr("EagleTree on Flexi-Port")); break; - case MS4525: + case AIRSPEED_MS4525: summary.append(tr("MS4525 based on Flexi-Port")); break; default: summary.append(tr("Unknown")); } } - - /* - summary.append("
"); - summary.append("").append(tr("Reboot required: ")).append(""); - summary.append(isRestartNeeded() ? tr("Yes") : tr("No")); - */ return summary; } @@ -425,7 +424,6 @@ void SetupWizard::createPages() setPage(PAGE_ESC, new EscPage(this)); setPage(PAGE_SERVO, new ServoPage(this)); setPage(PAGE_BIAS_CALIBRATION, new BiasCalibrationPage(this)); - // setPage(PAGE_REVO_CALIBRATION, new RevoCalibrationPage(this)); setPage(PAGE_OUTPUT_CALIBRATION, new OutputCalibrationPage(this)); setPage(PAGE_SUMMARY, new SummaryPage(this)); setPage(PAGE_SAVE, new SavePage(this)); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 0e37d5128..1999b2807 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -152,6 +152,7 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() } break; case VehicleConfigurationSource::CONTROLLER_REVO: + case VehicleConfigurationSource::CONTROLLER_NANO: // Reset all ports data.RM_RcvrPort = HwSettings::RM_RCVRPORT_DISABLED; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 635a35730..ccc6ba433 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -64,8 +64,8 @@ public: enum ESC_TYPE { ESC_RAPID, ESC_STANDARD, ESC_UNKNOWN }; enum SERVO_TYPE { SERVO_ANALOG, SERVO_DIGITAL, SERVO_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN }; - enum AIRSPEED_TYPE { ESTIMATE, EAGLETREE, MS4525 }; - enum GPS_TYPE { GPS_PLAT, GPS_UBX, GPS_NMEA, GPS_DISABLED }; + enum AIRSPEED_TYPE { AIRSPEED_ESTIMATE, AIRSPEED_EAGLETREE, AIRSPEED_MS4525, AIRSPEED_DISABLED }; + enum GPS_TYPE { GPS_PLATINUM, GPS_UBX, GPS_NMEA, GPS_DISABLED }; enum RADIO_SETTING { RADIO_TELEMETRY, RADIO_DISABLED }; virtual VehicleConfigurationSource::CONTROLLER_TYPE getControllerType() const = 0; From 240afd1f2f0dc8469b99cb06c5a747023b9a62e9 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Fri, 5 Sep 2014 21:25:12 +0200 Subject: [PATCH 142/203] OP-1222 Artwork : Added airspeed stuff + connectors - Resized all frames --- .../resources/connection-diagrams.svg | 1498 +++++++++++++---- 1 file changed, 1147 insertions(+), 351 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg index 138817d6c..73b572c98 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -12,8 +12,8 @@ xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd" xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape" id="svg12651" - height="519.51434" - width="1078.6002" + height="839.08447" + width="1309.343" version="1.1" inkscape:version="0.48.5 r10040" sodipodi:docname="connection-diagrams.svg"> @@ -30,13 +30,13 @@ inkscape:window-height="928" id="namedview4616" showgrid="false" - inkscape:zoom="0.70710678" - inkscape:cx="652.95764" - inkscape:cy="123.09779" + inkscape:zoom="0.5" + inkscape:cx="987.12085" + inkscape:cy="286.13827" inkscape:window-x="0" inkscape:window-y="27" inkscape:window-maximized="1" - inkscape:current-layer="svg12651" + inkscape:current-layer="nano-OPGPS-v9" fit-margin-top="15" fit-margin-left="15" fit-margin-right="15" @@ -47,109 +47,121 @@ inkscape:snap-global="true" inkscape:snap-bbox="true" inkscape:object-paths="true" - inkscape:snap-bbox-midpoints="true"> + inkscape:snap-bbox-midpoints="true" + inkscape:snap-bbox-edge-midpoints="true"> + id="grid19003" + empspacing="3" + visible="true" + enabled="true" + snapvisiblegridlinesonly="true" + originx="9.5291677px" + originy="248.19275px" /> + style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + transform="matrix(0.3,0,0,0.3,-0.69,0)" + inkscape:connector-curvature="0" /> + style="overflow:visible"> + style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + transform="matrix(-0.3,0,0,-0.3,0.69,0)" + inkscape:connector-curvature="0" /> + style="overflow:visible"> + d="M 0,0 L 5,-5 L -12.5,0 L 5,5 L 0,0 z" + style="fill-rule:evenodd;stroke:#000000;stroke-width:1pt" + transform="matrix(-0.2,0,0,-0.2,-1.2,0)" + inkscape:connector-curvature="0" /> + d="m -2.5,-1 c 0,2.76 -2.24,5 -5,5 c -2.76,0 -5,-2.24 -5,-5 c 0,-2.76 2.24,-5 5,-5 c 2.76,0 5,2.24 5,5 z" + style="fill-rule:evenodd;stroke:#000000;stroke-width:1pt" + transform="matrix(0.2,0,0,0.2,1.48,0.2)" + inkscape:connector-curvature="0" /> + d="m -2.5,-1 c 0,2.76 -2.24,5 -5,5 c -2.76,0 -5,-2.24 -5,-5 c 0,-2.76 2.24,-5 5,-5 c 2.76,0 5,2.24 5,5 z" + style="fill-rule:evenodd;stroke:#000000;stroke-width:1pt" + transform="matrix(0.4,0,0,0.4,2.96,0.4)" + inkscape:connector-curvature="0" /> @@ -176,7 +188,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10073"> @@ -208,7 +220,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10105"> @@ -237,7 +249,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10165"> @@ -245,7 +257,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10181"> @@ -261,7 +273,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10213"> @@ -277,7 +289,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10269"> @@ -285,7 +297,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10285"> @@ -301,7 +313,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10317"> @@ -317,7 +329,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4329"> @@ -325,7 +337,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4345"> @@ -341,7 +353,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4377"> @@ -373,7 +385,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4437"> @@ -381,7 +393,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4453"> @@ -397,7 +409,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4485"> @@ -421,7 +433,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4925"> @@ -429,7 +441,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4941"> @@ -445,7 +457,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4973"> @@ -474,7 +486,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7903"> @@ -482,7 +494,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7919"> @@ -498,7 +510,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7951"> @@ -527,7 +539,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5467"> @@ -535,7 +547,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5483"> @@ -543,7 +555,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5499"> @@ -551,7 +563,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5515"> @@ -559,7 +571,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5553"> @@ -575,7 +587,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5585"> @@ -591,7 +603,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5617"> @@ -607,7 +619,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5649"> @@ -623,7 +635,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5681"> @@ -639,7 +651,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5713"> @@ -655,7 +667,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5745"> @@ -671,7 +683,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5777"> @@ -700,7 +712,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7159"> @@ -708,7 +720,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7175"> @@ -724,7 +736,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7207"> @@ -740,7 +752,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7239"> @@ -748,7 +760,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7255"> @@ -764,7 +776,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7287"> @@ -780,7 +792,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7319"> @@ -788,7 +800,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7335"> @@ -804,7 +816,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7367"> @@ -820,7 +832,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7423"> @@ -828,7 +840,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7439"> @@ -844,7 +856,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7471"> @@ -860,7 +872,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7503"> @@ -868,7 +880,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7519"> @@ -884,7 +896,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7551"> @@ -900,7 +912,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7583"> @@ -908,7 +920,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7599"> @@ -924,7 +936,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7631"> @@ -953,7 +965,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5841"> @@ -961,7 +973,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5857"> @@ -969,7 +981,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5873"> @@ -977,7 +989,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5889"> @@ -985,7 +997,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5905"> @@ -1001,7 +1013,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5937"> @@ -1017,7 +1029,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5969"> @@ -1033,7 +1045,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6001"> @@ -1049,7 +1061,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6033"> @@ -1065,7 +1077,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6065"> @@ -1081,7 +1093,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6097"> @@ -1097,7 +1109,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6129"> @@ -1113,7 +1125,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6169"> @@ -1121,7 +1133,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6185"> @@ -1137,7 +1149,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6217"> @@ -1153,7 +1165,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6273"> @@ -1161,7 +1173,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6289"> @@ -1177,7 +1189,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6321"> @@ -1206,7 +1218,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5049"> @@ -1214,7 +1226,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5065"> @@ -1222,7 +1234,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5081"> @@ -1230,7 +1242,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5097"> @@ -1238,7 +1250,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5135"> @@ -1254,7 +1266,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5167"> @@ -1270,7 +1282,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5199"> @@ -1286,7 +1298,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5231"> @@ -1302,7 +1314,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5263"> @@ -1318,7 +1330,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5295"> @@ -1342,7 +1354,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5327"> @@ -1350,7 +1362,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5359"> @@ -1693,7 +1705,7 @@ @@ -1708,7 +1720,7 @@ inkscape:connector-curvature="0" id="path6056-4" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 -2.2072895,0.01601326 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -1736,7 +1748,7 @@ inkscape:connector-curvature="0" id="path21212" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 -2.2072895,0.01601326 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -1764,7 +1776,7 @@ inkscape:connector-curvature="0" id="path21220" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 -2.2072895,0.01601326 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> + horiz-adv-x="2048" + horiz-origin-x="0" + horiz-origin-y="0" + vert-origin-x="45" + vert-origin-y="90" + vert-adv-y="90"> + transform="scale(4.8828125e-4,-4.8828125e-4)"> + d="M 580,1141 L 1163,571 L 580,0 L -4,571 l 584,570 z" + id="path24979" + inkscape:connector-curvature="0" /> + transform="scale(4.8828125e-4,-4.8828125e-4)"> + d="m 8,1128 l 1129,0 L 1137,0 L 8,0 l 0,1128 z" + id="path24982" + inkscape:connector-curvature="0" /> + transform="scale(4.8828125e-4,-4.8828125e-4)"> + d="M 174,0 L 602,739 L 174,1481 L 1456,739 L 174,0 z M 1358,739 L 309,1346 L 659,739 l 699,0 z" + id="path24985" + inkscape:connector-curvature="0" /> + transform="scale(4.8828125e-4,-4.8828125e-4)"> + d="M 2015,739 L 1276,0 L 717,0 l 543,543 l -1086,0 l 0,393 l 1086,0 l -543,545 l 557,0 l 741,-742 z" + id="path24988" + inkscape:connector-curvature="0" /> + transform="scale(4.8828125e-4,-4.8828125e-4)"> + d="M 0,-2 C -7,14 -16,27 -25,37 L 356,567 C 262,823 215,952 215,954 c 0,25 13,38 40,38 c 9,0 21,-2 34,-5 c 21,4 42,12 65,25 l 27,-13 L 492,748 l 280,301 l 64,-25 l 24,25 c 21,-10 41,-24 62,-43 C 886,937 835,863 770,784 C 769,783 710,716 594,584 L 774,223 c 0,-27 -21,-55 -63,-84 l 16,-20 C 717,90 699,76 672,76 C 641,76 570,178 457,381 L 164,-76 c -22,-34 -53,-51 -92,-51 c -42,0 -63,17 -64,51 c -7,9 -10,24 -10,44 c 0,9 1,19 2,30 z" + id="path24991" + inkscape:connector-curvature="0" /> + transform="scale(4.8828125e-4,-4.8828125e-4)"> + d="M 285,-33 C 182,-33 111,30 74,156 C 52,228 41,333 41,471 c 0,78 14,145 41,201 c 34,71 87,106 158,106 c 53,0 88,-31 106,-94 l 23,-176 c 8,-64 28,-97 59,-98 l 735,706 c 11,11 33,17 66,17 c 42,0 63,-15 63,-46 l 0,-122 c 0,-36 -10,-64 -30,-84 L 442,47 C 390,-6 338,-33 285,-33 z" + id="path24994" + inkscape:connector-curvature="0" /> + transform="scale(4.8828125e-4,-4.8828125e-4)"> + d="M 813,0 C 632,0 489,54 383,161 C 276,268 223,411 223,592 c 0,181 53,324 160,431 c 106,107 249,161 430,161 c 179,0 323,-54 432,-161 c 108,-107 162,-251 162,-431 c 0,-180 -54,-324 -162,-431 C 1136,54 992,0 813,0 z" + id="path24997" + inkscape:connector-curvature="0" /> + transform="scale(4.8828125e-4,-4.8828125e-4)"> + d="m 346,457 c -73,0 -137,26 -191,78 C 101,586 74,649 74,723 c 0,73 27,136 81,188 c 54,52 118,78 191,78 c 73,0 134,-26 185,-79 c 51,-51 77,-114 77,-187 C 608,648 583,586 532,535 C 482,483 420,457 346,457 z" + id="path25000" + inkscape:connector-curvature="0" /> + transform="scale(4.8828125e-4,-4.8828125e-4)"> + d="m -4,459 l 1139,0 l 0,147 L -4,606 l 0,-147 z" + id="path25003" + inkscape:connector-curvature="0" /> + inkscape:collect="always" + gradientTransform="translate(312.54994,258.42874)" /> @@ -7438,7 +7465,8 @@ x1="313.46094" id="linearGradient4133-1-3" xlink:href="#linearGradient4123-8-6" - inkscape:collect="always" /> + inkscape:collect="always" + gradientTransform="translate(312.54994,258.42874)" /> + style="display:none" + sodipodi:insensitive="true" + transform="translate(9.5291677,71.377308)"> + style="display:inline" + transform="translate(9.5291677,71.377308)"> @@ -9201,7 +9231,7 @@ inkscape:groupmode="layer" id="layer3" inkscape:label="ppm-nano" - style="display:none" + style="display:inline" sodipodi:insensitive="true"> @@ -9477,7 +9507,8 @@ + inkscape:label="gps" + transform="translate(9.5291677,71.377308)"> + points="191.036,13.319 186.194,11.031 181.129,13.319 186.083,4.74 " /> + transform="matrix(0,0.61953016,-0.61953016,0,444.76031,745.86288)" /> + transform="matrix(0,0.61953016,-0.61953016,0,748.33009,1049.4331)" /> @@ -12346,14 +12377,13 @@ inkscape:groupmode="layer" id="layer39" inkscape:label="nano-OPGPS-v9" - style="display:none" - sodipodi:insensitive="true"> + style="display:inline"> + y="860.77875" /> + transform="matrix(0,-0.52050376,0.52050376,0,73.486791,1123.372)" /> + transform="matrix(0,-0.52050376,0.52050376,0,-181.56005,868.32659)" /> @@ -12540,26 +12570,26 @@ style="fill:#ff7802;fill-opacity:1" height="8.6985588" width="11.38681" - y="1038.3141" + y="1142.0348" x="260.17172" id="rect7791-5" /> + transform="matrix(0.84015887,0,0,0.84015887,76.994784,325.36783)"> + transform="matrix(2.0369727,0,0,1.9930231,-213.6161,865.86491)" /> + points="191.036,13.319 186.194,11.031 181.129,13.319 186.083,4.74 " /> + transform="translate(23.226901,36.302528)"> + inkscape:label="airspeed-sensors" + transform="translate(9.5291677,71.377308)"> + style="display:none"> + id="g4145" + transform="translate(312.54994,258.42874)"> @@ -12872,14 +12904,14 @@ transform="scale(1,-1)" height="6.6888146" width="3.5201147" - y="-477.83289" - x="155.04897" + y="-736.26166" + x="467.59891" style="fill:#8c8989;display:inline" inkscape:transform-center-x="-52.437732" inkscape:transform-center-y="43.141303" /> + style="fill:url(#linearGradient14739-8-0);fill-opacity:1;stroke:none" + transform="translate(312.54994,258.42874)"> + id="g4097-6" + transform="translate(312.54994,258.42874)"> @@ -13135,8 +13169,8 @@ transform="scale(1,-1)" height="6.6888146" width="3.5201147" - y="-505.83289" - x="155.04897" + y="-764.26166" + x="467.59891" style="fill:#8c8989;display:inline" inkscape:transform-center-x="-52.437732" inkscape:transform-center-y="43.141303" /> @@ -13144,8 +13178,8 @@ inkscape:transform-center-y="43.141303" inkscape:transform-center-x="-52.764729" style="fill:#e9dcdc;display:inline" - x="149.4836" - y="-519.83289" + x="462.03354" + y="-778.26166" width="15.304846" height="6.6888146" transform="scale(1,-1)" @@ -13154,8 +13188,8 @@ inkscape:transform-center-y="43.141303" inkscape:transform-center-x="-52.437732" style="fill:#8c8989;display:inline" - x="155.04897" - y="-519.83289" + x="467.59891" + y="-778.26166" width="3.5201147" height="6.6888146" transform="scale(1,-1)" @@ -13165,10 +13199,181 @@ id="rect4114" width="61.019764" height="67.917648" - x="89.141914" - y="460.66672" + x="401.69186" + y="719.09546" rx="1.0435867" ry="1.0435867" /> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + style="display:none"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + style="display:none"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -15450,12 +16241,13 @@ inkscape:groupmode="layer" id="layer11" inkscape:label="boards" - style="display:inline"> + style="display:inline" + transform="translate(9.5291677,71.377308)"> + points="186.083,4.74 191.036,13.319 186.194,11.031 181.129,13.319 " /> + points="36.083,4.74 41.036,13.319 36.194,11.031 31.129,13.319 " /> - @@ -7457,16 +7447,6 @@ offset="1" style="stop-color:#4e4e4e;stop-opacity:0;" /> - - @@ -7804,15 +7775,6 @@ offset="1" style="stop-color:#4e4e4e;stop-opacity:0;" /> - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -8518,7 +8648,7 @@ image/svg+xml - + @@ -8550,54 +8680,54 @@ inkscape:groupmode="layer" id="layer19" inkscape:label="pwm" - style="display:none" + style="display:inline" sodipodi:insensitive="true"> @@ -8650,19 +8780,19 @@ style="font-size:22.39999962px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#488eff;font-family:Sans" id="text9734-2"> @@ -8670,23 +8800,23 @@ style="font-size:22.39999962px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffdc00;font-family:Sans" id="text9734-2-6"> @@ -8694,15 +8824,15 @@ style="font-size:22.39999962px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-indent:0;text-align:start;text-decoration:none;line-height:125%;letter-spacing:0px;word-spacing:0px;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:start;baseline-shift:baseline;color:#000000;fill:#73ff00;fill-rule:nonzero;enable-background:accumulate;font-family:Sans" id="text9734-2-6-4"> @@ -8710,43 +8840,43 @@ style="font-size:22.39999962px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-indent:0;text-align:end;text-decoration:none;line-height:125%;letter-spacing:0px;word-spacing:0px;text-transform:none;direction:ltr;block-progression:tb;writing-mode:lr-tb;text-anchor:end;baseline-shift:baseline;color:#000000;fill:#ff7e00;fill-rule:nonzero;enable-background:accumulate;font-family:Sans" id="text9734-2-6-4-2"> @@ -8762,72 +8892,72 @@ id="ppm"> @@ -8837,7 +8967,8 @@ inkscape:groupmode="layer" id="layer21" inkscape:label="sbus" - style="display:none"> + style="display:none" + sodipodi:insensitive="true"> + style="display:none" + sodipodi:insensitive="true"> @@ -9030,95 +9162,95 @@ sodipodi:nodetypes="ccc" style="fill:none;stroke:#6b6b6b;stroke-width:1.21428466;stroke-linecap:butt;stroke-linejoin:miter" inkscape:connector-curvature="0" - d="m 423.36407,327.33254 l 105.19993,-0.556 l 0,-86.2622" + d="M 423.36407,327.33254 L 528.564,326.77654 L 528.564,240.51434" id="path8856-0" /> @@ -9231,7 +9363,7 @@ inkscape:groupmode="layer" id="layer3" inkscape:label="ppm-nano" - style="display:inline" + style="display:none" sodipodi:insensitive="true"> @@ -9239,34 +9371,34 @@ sodipodi:nodetypes="ccc" style="fill:none;stroke:#6b6b6b;stroke-width:1.21428466;stroke-linecap:butt;stroke-linejoin:miter;display:inline" inkscape:connector-curvature="0" - d="m 423.36407,327.33254 l 105.19993,-0.556 l 0,-86.2622" + d="M 423.36407,327.33254 L 528.564,326.77654 L 528.564,240.51434" id="path8856-0-2" /> @@ -9275,39 +9407,39 @@ style="font-size:22.39999962px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;text-align:start;line-height:125%;letter-spacing:0px;word-spacing:0px;writing-mode:lr-tb;text-anchor:start;fill:#ffffff;font-family:Sans"> @@ -9516,16 +9648,14 @@ style="display:none" sodipodi:insensitive="true"> + id="generic-nmea"> + transform="matrix(0,0.77129601,-0.77129601,0,1456.0461,377.01359)"> @@ -9654,51 +9784,52 @@ style="fill:#2e2f2e;fill-opacity:1;fill-rule:evenodd;stroke:none;display:inline" /> + style="fill:url(#linearGradient16431);fill-opacity:1;fill-rule:evenodd;stroke:#0e0e0e;stroke-width:0.66049641;stroke-opacity:1" /> @@ -9706,39 +9837,39 @@ inkscape:transform-center-y="28.155826" inkscape:transform-center-x="-50.291428" style="fill:#e9dcdc;display:inline" - x="252.71611" - y="-995.87787" - width="14.587445" - height="5.7969942" - transform="scale(1,-1)" + x="554.66888" + y="686.51526" + width="11.251238" + height="4.4711986" + transform="matrix(0,1,1,0,0,0)" id="rect10590" /> @@ -9746,53 +9877,54 @@ inkscape:transform-center-y="28.155764" inkscape:transform-center-x="-50.291428" style="fill:#e9dcdc;display:inline" - x="252.71611" - y="-1016.4301" - width="14.587445" - height="5.7969942" - transform="scale(1,-1)" + x="554.66888" + y="670.66339" + width="11.251238" + height="4.4711986" + transform="matrix(0,1,1,0,0,0)" id="rect10598" /> + style="fill:#dbddde;fill-opacity:1;fill-rule:evenodd;stroke:#393a3e;stroke-width:0.66049641;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + transform="matrix(0,0.94133169,-0.79502748,0,1550.3162,532.85791)"> @@ -10227,98 +10359,98 @@ inkscape:connector-curvature="0" id="path13212" style="font-weight:normal;-inkscape-font-specification:Arial Narrow Condensed" - d="m 379.71034,1197.185 l 0,-1.8195 l 5.38448,-0.011 l 0,5.7547 c -0.82514,0.8039 -1.67847,1.4105 -2.56001,1.8195 c -0.88155,0.402 -1.78778,0.603 -2.71868,0.603 c -1.24122,0 -2.34844,-0.3103 -3.32166,-0.9309 c -0.97323,-0.6207 -1.74546,-1.5269 -2.3167,-2.7187 c -0.56419,-1.1919 -0.84628,-2.6235 -0.84628,-4.2949 c 0,-1.6926 0.28562,-3.1665 0.85686,-4.4218 c 0.57124,-1.2553 1.31879,-2.1792 2.24265,-2.7716 c 0.92385,-0.5994 2.01697,-0.8992 3.27934,-0.8992 c 0.93091,0 1.74545,0.1728 2.44364,0.5184 c 0.69818,0.3455 1.27294,0.8357 1.72431,1.4704 c 0.45133,0.6347 0.78985,1.5057 1.01553,2.6129 l -1.51273,0.5077 c -0.20452,-0.8744 -0.46194,-1.5268 -0.77223,-1.957 c -0.31031,-0.4372 -0.71935,-0.7793 -1.22711,-1.0261 c -0.50778,-0.2468 -1.07902,-0.3702 -1.71372,-0.3703 c -0.92386,10e-5 -1.72078,0.2257 -2.39075,0.6771 c -0.66292,0.4443 -1.1989,1.1389 -1.60793,2.0839 c -0.40199,0.9451 -0.60298,2.0981 -0.60298,3.4592 c 0,2.0734 0.43372,3.6285 1.30116,4.6652 c 0.86743,1.0296 1.99581,1.5444 3.38513,1.5444 c 0.66291,0 1.33994,-0.1587 2.03108,-0.476 c 0.69817,-0.3174 1.25178,-0.6947 1.66083,-1.1319 l 0,-2.888 l -3.73423,0" /> + d="M 379.71034,1197.185 L 379.71034,1195.3655 L 385.09482,1195.3545 L 385.09482,1201.1092 C 384.26968,1201.9131 383.41635,1202.5197 382.53481,1202.9287 C 381.65326,1203.3307 380.74703,1203.5317 379.81613,1203.5317 C 378.57491,1203.5317 377.46769,1203.2214 376.49447,1202.6008 C 375.52124,1201.9801 374.74901,1201.0739 374.17777,1199.8821 C 373.61358,1198.6902 373.33149,1197.2586 373.33149,1195.5872 C 373.33149,1193.8946 373.61711,1192.4207 374.18835,1191.1654 C 374.75959,1189.9101 375.50714,1188.9862 376.431,1188.3938 C 377.35485,1187.7944 378.44797,1187.4946 379.71034,1187.4946 C 380.64125,1187.4946 381.45579,1187.6674 382.15398,1188.013 C 382.85216,1188.3585 383.42692,1188.8487 383.87829,1189.4834 C 384.32962,1190.1181 384.66814,1190.9891 384.89382,1192.0963 L 383.38109,1192.604 C 383.17657,1191.7296 382.91915,1191.0772 382.60886,1190.647 C 382.29855,1190.2098 381.88951,1189.8677 381.38175,1189.6209 C 380.87397,1189.3741 380.30273,1189.2507 379.66803,1189.2506 C 378.74417,1189.2507 377.94725,1189.4763 377.27728,1189.9277 C 376.61436,1190.372 376.07838,1191.0666 375.66935,1192.0116 C 375.26736,1192.9567 375.06637,1194.1097 375.06637,1195.4708 C 375.06637,1197.5442 375.50009,1199.0993 376.36753,1200.136 C 377.23496,1201.1656 378.36334,1201.6804 379.75266,1201.6804 C 380.41557,1201.6804 381.0926,1201.5217 381.78374,1201.2044 C 382.48191,1200.887 383.03552,1200.5097 383.44457,1200.0725 L 383.44457,1197.1845 L 379.71034,1197.1845" /> + d="M 390.8178,1203.2677 L 390.8178,1189.5897 L 386.6287,1189.5897 L 386.6287,1187.7596 L 396.71004,1187.7596 L 396.71004,1189.5897 L 392.49979,1189.5897 L 392.49979,1203.2677 L 390.8178,1203.2677" /> + d="M 398.43434,1203.2677 L 398.43434,1187.7596 L 403.22642,1187.7596 C 404.35479,1187.7596 405.18697,1187.8586 405.72295,1188.0558 C 406.45639,1188.3238 407.04173,1188.821 407.47899,1189.5473 C 407.91622,1190.2738 408.13485,1191.1659 408.13486,1192.2237 C 408.13485,1193.6201 407.7787,1194.759 407.06643,1195.6406 C 406.35413,1196.5221 405.12349,1196.9629 403.37452,1196.9629 L 400.11633,1196.9629 L 400.11633,1203.2677 L 398.43434,1203.2677 M 400.11633,1195.1328 L 403.40625,1195.1328 C 404.44294,1195.1328 405.20107,1194.9001 405.68064,1194.4346 C 406.16019,1193.9621 406.39997,1193.2534 406.39998,1192.3083 C 406.39997,1191.6948 406.28008,1191.1694 406.04031,1190.7321 C 405.80757,1190.2949 405.52195,1189.9952 405.18345,1189.833 C 404.85198,1189.6708 404.249,1189.5897 403.37452,1189.5897 L 400.11633,1189.5897 L 400.11633,1195.1328" /> + d="M 407.59535,1203.2677 L 412.48263,1187.7596 L 414.29156,1187.7596 L 419.4962,1203.2677 L 417.57091,1203.2677 L 416.08991,1198.5708 L 410.77949,1198.5708 L 409.38312,1203.2677 L 407.59535,1203.2677 M 411.2661,1196.8994 L 415.57156,1196.8994 L 414.24925,1192.6045 C 413.8402,1191.2858 413.54048,1190.2138 413.35007,1189.3887 C 413.18786,1190.3831 412.95866,1191.3704 412.66247,1192.3507 L 411.2661,1196.8994" /> + d="M 420.19438,1195.6194 C 420.19438,1193.0171 420.54347,1191.046 421.24165,1189.706 C 421.94689,1188.3661 422.98358,1187.6961 424.35174,1187.6961 C 425.56474,1187.6961 426.52033,1188.2391 427.21852,1189.3252 C 428.0648,1190.6369 428.48794,1192.735 428.48795,1195.6194 C 428.48794,1198.2076 428.13885,1200.1752 427.44067,1201.5222 C 426.74248,1202.8622 425.70579,1203.5322 424.33059,1203.5322 C 423.11758,1203.5322 422.1232,1202.9398 421.34744,1201.755 C 420.57873,1200.5702 420.19438,1198.525 420.19438,1195.6194 M 421.79174,1195.6194 C 421.79174,1198.1371 422.03152,1199.8262 422.51108,1200.6865 C 422.99769,1201.5399 423.61829,1201.9665 424.3729,1201.9665 C 425.08518,1201.9665 425.68111,1201.5328 426.16067,1200.6654 C 426.64022,1199.7979 426.88,1198.116 426.88001,1195.6194 C 426.88,1193.0947 426.6367,1191.4057 426.15009,1190.5523 C 425.67053,1189.699 425.04639,1189.2723 424.27769,1189.2723 C 423.57245,1189.2723 422.98006,1189.706 422.5005,1190.5735 C 422.02799,1191.4409 421.79174,1193.1229 421.79174,1195.6194" /> + d="M 435.97755,1203.2677 L 434.41193,1203.2677 L 434.41193,1191.1341 C 434.05225,1191.5573 433.56916,1191.991 432.96267,1192.4353 C 432.35616,1192.8725 431.79903,1193.204 431.29126,1193.4297 L 431.29126,1191.589 C 432.15164,1191.0953 432.90977,1190.4924 433.56564,1189.7801 C 434.22856,1189.0678 434.69401,1188.3731 434.96201,1187.6961 L 435.97755,1187.6961 L 435.97755,1203.2677" /> + d="M 439.99739,1195.6194 C 439.99739,1193.0171 440.34648,1191.046 441.04466,1189.706 C 441.7499,1188.3661 442.78659,1187.6961 444.15475,1187.6961 C 445.36775,1187.6961 446.32334,1188.2391 447.02153,1189.3252 C 447.86781,1190.6369 448.29095,1192.735 448.29096,1195.6194 C 448.29095,1198.2076 447.94186,1200.1752 447.24368,1201.5222 C 446.54549,1202.8622 445.5088,1203.5322 444.13359,1203.5322 C 442.92059,1203.5322 441.92621,1202.9398 441.15045,1201.755 C 440.38174,1200.5702 439.99739,1198.525 439.99739,1195.6194 M 441.59475,1195.6194 C 441.59475,1198.1371 441.83452,1199.8262 442.31409,1200.6865 C 442.8007,1201.5399 443.4213,1201.9665 444.17591,1201.9665 C 444.88819,1201.9665 445.48411,1201.5328 445.96368,1200.6654 C 446.44323,1199.7979 446.68301,1198.116 446.68302,1195.6194 C 446.68301,1193.0947 446.43971,1191.4057 445.9531,1190.5523 C 445.47354,1189.699 444.8494,1189.2723 444.0807,1189.2723 C 443.37546,1189.2723 442.78307,1189.706 442.30351,1190.5735 C 441.831,1191.4409 441.59475,1193.1229 441.59475,1195.6194" /> + transform="matrix(0,0.77129601,-0.77129601,0,1480.0498,353.39548)"> - - - - - - + + + + @@ -10713,467 +10836,442 @@ style="display:none" sodipodi:insensitive="true"> - - - - - - + id="OPGPS-v9"> + id="rect14138-8-9-5" + x="620.07581" + y="520.27533" + width="35.854359" + height="26.855732" + style="fill:#f1a853;fill-opacity:1;stroke:#f1a853;stroke-width:3.93985224;stroke-linecap:round;stroke-linejoin:round;stroke-opacity:1;display:inline" /> + + + + + + + + + - - + id="g7368" + transform="matrix(0,-0.40146247,0.40146247,0,258.77791,716.87083)"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + - - - - - - - - - - - - - - - - - - - + id="path10322" + d="M 253.89355,989.09735 L 253.89355,979.21973 L 256.52129,979.21973 C 257.50051,979.21974 258.1406,979.26693 258.44157,979.36122 C 258.92219,979.51395 259.31747,979.83961 259.62742,980.3382 C 259.94184,980.83681 260.09906,981.47915 260.09907,982.26521 C 260.09906,982.97943 259.9643,983.57909 259.6948,984.06421 C 259.42528,984.54484 259.08839,984.88398 258.68413,985.08162 C 258.27985,985.27477 257.58361,985.37135 256.59541,985.37134 L 255.52409,985.37134 L 255.52409,989.09735 L 253.89355,989.09735 M 255.52409,980.8907 L 255.52409,983.69363 L 256.42696,983.69363 C 257.03336,983.69364 257.44437,983.65093 257.65998,983.56561 C 257.88008,983.48031 258.05975,983.32755 258.199,983.10744 C 258.33825,982.88285 258.40787,982.60885 258.40788,982.28543 C 258.40787,981.95753 258.33598,981.68128 258.19227,981.45668 C 258.04852,981.23209 257.87109,981.08161 257.65998,981.00525 C 257.44886,980.92885 257.00192,980.89071 256.31916,980.8907 L 255.52409,980.8907" /> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + id="path10324" + d="M 261.43315,989.09735 L 261.43315,979.21973 L 262.98959,979.21973 L 262.98959,989.09735 L 261.43315,989.09735" /> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -11184,17 +11282,15 @@ style="display:none" sodipodi:insensitive="true"> + id="nano-generic-nmea"> + transform="matrix(0,0.77129601,-0.77129601,0,1393.0266,295.28849)"> @@ -11323,52 +11419,52 @@ style="fill:#2e2f2e;fill-opacity:1;fill-rule:evenodd;stroke:none;display:inline" /> @@ -11376,39 +11472,39 @@ inkscape:transform-center-y="50.291435" inkscape:transform-center-x="28.155837" style="fill:#e9dcdc;display:inline" - x="867.74518" - y="759.60815" - width="14.587445" - height="5.7969942" + x="472.94382" + y="623.31763" + width="11.251238" + height="4.4711986" transform="matrix(0,1,1,0,0,0)" id="rect10590-3" /> @@ -11416,54 +11512,54 @@ inkscape:transform-center-y="50.291435" inkscape:transform-center-x="28.155775" style="fill:#e9dcdc;display:inline" - x="867.74518" - y="739.05591" - width="14.587445" - height="5.7969942" + x="472.94382" + y="607.46576" + width="11.251238" + height="4.4711986" transform="matrix(0,1,1,0,0,0)" id="rect10598-8" /> + transform="matrix(0,0.94133169,-0.79502748,0,1487.1189,451.1328)"> @@ -11898,98 +11994,98 @@ inkscape:connector-curvature="0" id="path13212-0" style="font-weight:normal;-inkscape-font-specification:Arial Narrow Condensed" - d="m 379.71034,1197.185 l 0,-1.8195 l 5.38448,-0.011 l 0,5.7547 c -0.82514,0.8039 -1.67847,1.4105 -2.56001,1.8195 c -0.88155,0.402 -1.78778,0.603 -2.71868,0.603 c -1.24122,0 -2.34844,-0.3103 -3.32166,-0.9309 c -0.97323,-0.6207 -1.74546,-1.5269 -2.3167,-2.7187 c -0.56419,-1.1919 -0.84628,-2.6235 -0.84628,-4.2949 c 0,-1.6926 0.28562,-3.1665 0.85686,-4.4218 c 0.57124,-1.2553 1.31879,-2.1792 2.24265,-2.7716 c 0.92385,-0.5994 2.01697,-0.8992 3.27934,-0.8992 c 0.93091,0 1.74545,0.1728 2.44364,0.5184 c 0.69818,0.3455 1.27294,0.8357 1.72431,1.4704 c 0.45133,0.6347 0.78985,1.5057 1.01553,2.6129 l -1.51273,0.5077 c -0.20452,-0.8744 -0.46194,-1.5268 -0.77223,-1.957 c -0.31031,-0.4372 -0.71935,-0.7793 -1.22711,-1.0261 c -0.50778,-0.2468 -1.07902,-0.3702 -1.71372,-0.3703 c -0.92386,10e-5 -1.72078,0.2257 -2.39075,0.6771 c -0.66292,0.4443 -1.1989,1.1389 -1.60793,2.0839 c -0.40199,0.9451 -0.60298,2.0981 -0.60298,3.4592 c 0,2.0734 0.43372,3.6285 1.30116,4.6652 c 0.86743,1.0296 1.99581,1.5444 3.38513,1.5444 c 0.66291,0 1.33994,-0.1587 2.03108,-0.476 c 0.69817,-0.3174 1.25178,-0.6947 1.66083,-1.1319 l 0,-2.888 l -3.73423,0" /> + d="M 379.71034,1197.185 L 379.71034,1195.3655 L 385.09482,1195.3545 L 385.09482,1201.1092 C 384.26968,1201.9131 383.41635,1202.5197 382.53481,1202.9287 C 381.65326,1203.3307 380.74703,1203.5317 379.81613,1203.5317 C 378.57491,1203.5317 377.46769,1203.2214 376.49447,1202.6008 C 375.52124,1201.9801 374.74901,1201.0739 374.17777,1199.8821 C 373.61358,1198.6902 373.33149,1197.2586 373.33149,1195.5872 C 373.33149,1193.8946 373.61711,1192.4207 374.18835,1191.1654 C 374.75959,1189.9101 375.50714,1188.9862 376.431,1188.3938 C 377.35485,1187.7944 378.44797,1187.4946 379.71034,1187.4946 C 380.64125,1187.4946 381.45579,1187.6674 382.15398,1188.013 C 382.85216,1188.3585 383.42692,1188.8487 383.87829,1189.4834 C 384.32962,1190.1181 384.66814,1190.9891 384.89382,1192.0963 L 383.38109,1192.604 C 383.17657,1191.7296 382.91915,1191.0772 382.60886,1190.647 C 382.29855,1190.2098 381.88951,1189.8677 381.38175,1189.6209 C 380.87397,1189.3741 380.30273,1189.2507 379.66803,1189.2506 C 378.74417,1189.2507 377.94725,1189.4763 377.27728,1189.9277 C 376.61436,1190.372 376.07838,1191.0666 375.66935,1192.0116 C 375.26736,1192.9567 375.06637,1194.1097 375.06637,1195.4708 C 375.06637,1197.5442 375.50009,1199.0993 376.36753,1200.136 C 377.23496,1201.1656 378.36334,1201.6804 379.75266,1201.6804 C 380.41557,1201.6804 381.0926,1201.5217 381.78374,1201.2044 C 382.48191,1200.887 383.03552,1200.5097 383.44457,1200.0725 L 383.44457,1197.1845 L 379.71034,1197.1845" /> + d="M 390.8178,1203.2677 L 390.8178,1189.5897 L 386.6287,1189.5897 L 386.6287,1187.7596 L 396.71004,1187.7596 L 396.71004,1189.5897 L 392.49979,1189.5897 L 392.49979,1203.2677 L 390.8178,1203.2677" /> + d="M 398.43434,1203.2677 L 398.43434,1187.7596 L 403.22642,1187.7596 C 404.35479,1187.7596 405.18697,1187.8586 405.72295,1188.0558 C 406.45639,1188.3238 407.04173,1188.821 407.47899,1189.5473 C 407.91622,1190.2738 408.13485,1191.1659 408.13486,1192.2237 C 408.13485,1193.6201 407.7787,1194.759 407.06643,1195.6406 C 406.35413,1196.5221 405.12349,1196.9629 403.37452,1196.9629 L 400.11633,1196.9629 L 400.11633,1203.2677 L 398.43434,1203.2677 M 400.11633,1195.1328 L 403.40625,1195.1328 C 404.44294,1195.1328 405.20107,1194.9001 405.68064,1194.4346 C 406.16019,1193.9621 406.39997,1193.2534 406.39998,1192.3083 C 406.39997,1191.6948 406.28008,1191.1694 406.04031,1190.7321 C 405.80757,1190.2949 405.52195,1189.9952 405.18345,1189.833 C 404.85198,1189.6708 404.249,1189.5897 403.37452,1189.5897 L 400.11633,1189.5897 L 400.11633,1195.1328" /> + d="M 407.59535,1203.2677 L 412.48263,1187.7596 L 414.29156,1187.7596 L 419.4962,1203.2677 L 417.57091,1203.2677 L 416.08991,1198.5708 L 410.77949,1198.5708 L 409.38312,1203.2677 L 407.59535,1203.2677 M 411.2661,1196.8994 L 415.57156,1196.8994 L 414.24925,1192.6045 C 413.8402,1191.2858 413.54048,1190.2138 413.35007,1189.3887 C 413.18786,1190.3831 412.95866,1191.3704 412.66247,1192.3507 L 411.2661,1196.8994" /> + d="M 420.19438,1195.6194 C 420.19438,1193.0171 420.54347,1191.046 421.24165,1189.706 C 421.94689,1188.3661 422.98358,1187.6961 424.35174,1187.6961 C 425.56474,1187.6961 426.52033,1188.2391 427.21852,1189.3252 C 428.0648,1190.6369 428.48794,1192.735 428.48795,1195.6194 C 428.48794,1198.2076 428.13885,1200.1752 427.44067,1201.5222 C 426.74248,1202.8622 425.70579,1203.5322 424.33059,1203.5322 C 423.11758,1203.5322 422.1232,1202.9398 421.34744,1201.755 C 420.57873,1200.5702 420.19438,1198.525 420.19438,1195.6194 M 421.79174,1195.6194 C 421.79174,1198.1371 422.03152,1199.8262 422.51108,1200.6865 C 422.99769,1201.5399 423.61829,1201.9665 424.3729,1201.9665 C 425.08518,1201.9665 425.68111,1201.5328 426.16067,1200.6654 C 426.64022,1199.7979 426.88,1198.116 426.88001,1195.6194 C 426.88,1193.0947 426.6367,1191.4057 426.15009,1190.5523 C 425.67053,1189.699 425.04639,1189.2723 424.27769,1189.2723 C 423.57245,1189.2723 422.98006,1189.706 422.5005,1190.5735 C 422.02799,1191.4409 421.79174,1193.1229 421.79174,1195.6194" /> + d="M 435.97755,1203.2677 L 434.41193,1203.2677 L 434.41193,1191.1341 C 434.05225,1191.5573 433.56916,1191.991 432.96267,1192.4353 C 432.35616,1192.8725 431.79903,1193.204 431.29126,1193.4297 L 431.29126,1191.589 C 432.15164,1191.0953 432.90977,1190.4924 433.56564,1189.7801 C 434.22856,1189.0678 434.69401,1188.3731 434.96201,1187.6961 L 435.97755,1187.6961 L 435.97755,1203.2677" /> + d="M 439.99739,1195.6194 C 439.99739,1193.0171 440.34648,1191.046 441.04466,1189.706 C 441.7499,1188.3661 442.78659,1187.6961 444.15475,1187.6961 C 445.36775,1187.6961 446.32334,1188.2391 447.02153,1189.3252 C 447.86781,1190.6369 448.29095,1192.735 448.29096,1195.6194 C 448.29095,1198.2076 447.94186,1200.1752 447.24368,1201.5222 C 446.54549,1202.8622 445.5088,1203.5322 444.13359,1203.5322 C 442.92059,1203.5322 441.92621,1202.9398 441.15045,1201.755 C 440.38174,1200.5702 439.99739,1198.525 439.99739,1195.6194 M 441.59475,1195.6194 C 441.59475,1198.1371 441.83452,1199.8262 442.31409,1200.6865 C 442.8007,1201.5399 443.4213,1201.9665 444.17591,1201.9665 C 444.88819,1201.9665 445.48411,1201.5328 445.96368,1200.6654 C 446.44323,1199.7979 446.68301,1198.116 446.68302,1195.6194 C 446.68301,1193.0947 446.43971,1191.4057 445.9531,1190.5523 C 445.47354,1189.699 444.8494,1189.2723 444.0807,1189.2723 C 443.37546,1189.2723 442.78307,1189.706 442.30351,1190.5735 C 441.831,1191.4409 441.59475,1193.1229 441.59475,1195.6194" /> + transform="matrix(0,0.77129601,-0.77129601,0,1416.8525,271.67038)"> - - - - - - + + + + + id="nano-OPGPS-v8-ublox"> + d="M 751.7298,535.01081 L 751.7298,737.14902 C 751.7298,743.8214 746.35823,749.19302 739.68593,749.19302 L 537.54786,749.19302 C 530.87556,749.19302 525.50399,743.8214 525.50399,737.14902 L 525.50399,535.01081 C 525.50399,528.3385 530.87556,522.96694 537.54786,522.96694 L 739.68593,522.96694 C 746.35823,522.96694 751.7298,528.3385 751.7298,535.01081 z" + style="fill:#2d2b2c;fill-opacity:1;stroke:#ffd25c;stroke-width:4.97813463;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dashoffset:0" /> @@ -12110,31 +12198,31 @@ id="text4847-3"> + d="M 94.28441,672.04335 L 103.38147,672.04335 L 103.38147,696.4456 C 103.38146,700.31801 103.49415,702.8279 103.71954,703.97526 C 104.10881,705.81927 105.03081,707.30471 106.48554,708.43159 C 107.96072,709.538 109.96863,710.0912 112.50927,710.09119 C 115.09084,710.0912 117.03728,709.56873 118.3486,708.52379 C 119.65986,707.45838 120.44868,706.15734 120.71506,704.62066 C 120.98139,703.08401 121.11456,700.53315 121.1146,696.96807 L 121.1146,672.04335 L 130.21166,672.04335 L 130.21166,695.708 C 130.21162,701.11708 129.96575,704.93825 129.47406,707.17153 C 128.98229,709.40482 128.07053,711.2898 126.73879,712.82646 C 125.42747,714.36313 123.66543,715.59246 121.45266,716.51446 C 119.23983,717.41597 116.35091,717.86672 112.78587,717.86672 C 108.48318,717.86672 105.21521,717.37499 102.98194,716.39152 C 100.76913,715.38757 99.017332,714.09677 97.726542,712.51912 C 96.435736,710.921 95.585448,709.25116 95.175676,707.50959 C 94.581494,704.92801 94.284406,701.11708 94.28441,696.0768 L 94.28441,672.04335" /> + d="M 139.86192,672.04335 L 157.87164,672.04335 C 161.43668,672.04339 164.08999,672.19706 165.83157,672.50435 C 167.59358,672.79123 169.16098,673.4059 170.53377,674.34834 C 171.92698,675.29087 173.0846,676.55094 174.00664,678.12854 C 174.92859,679.68573 175.38959,681.43753 175.38963,683.38394 C 175.38959,685.49433 174.81591,687.43052 173.66857,689.19254 C 172.54164,690.95461 171.00498,692.27614 169.05857,693.15713 C 171.80404,693.95622 173.9144,695.31873 175.38963,697.24467 C 176.86479,699.17064 177.60239,701.43466 177.60243,704.03673 C 177.60239,706.08563 177.1209,708.08329 176.15797,710.02973 C 175.21544,711.95569 173.9144,713.50259 172.25484,714.67046 C 170.61569,715.81784 168.58729,716.5247 166.16964,716.79106 C 164.65343,716.95497 160.99617,717.05741 155.19785,717.09839 L 139.86192,717.09839 L 139.86192,672.04335 M 148.95898,679.54228 L 148.95898,689.96087 L 154.92125,689.96087 C 158.4658,689.9609 160.66835,689.90967 161.52891,689.8072 C 163.08604,689.62283 164.30512,689.09012 165.18617,688.20907 C 166.08765,687.30759 166.53841,686.12948 166.53844,684.67474 C 166.53841,683.28153 166.14912,682.15464 165.37057,681.29407 C 164.61246,680.41309 163.47532,679.88038 161.95917,679.69594 C 161.05764,679.59353 158.4658,679.54231 154.18365,679.54228 L 148.95898,679.54228 M 148.95898,697.4598 L 148.95898,709.50726 L 157.37991,709.50726 C 160.65811,709.50727 162.73772,709.41506 163.61877,709.23066 C 164.97101,708.9848 166.06716,708.39062 166.90724,707.44813 C 167.76774,706.48516 168.19801,705.20461 168.19804,703.60646 C 168.19801,702.25421 167.87018,701.10684 167.21457,700.16433 C 166.5589,699.22186 165.60616,698.53548 164.35637,698.1052 C 163.12701,697.67495 160.44297,697.45982 156.30424,697.4598 L 148.95898,697.4598" /> + d="M 185.56236,717.09839 L 185.56236,672.41215 L 194.65942,672.41215 L 194.65942,709.50726 L 217.27915,709.50726 L 217.27915,717.09839 L 185.56236,717.09839" /> + d="M 221.95061,694.84747 C 221.95061,690.25799 222.63698,686.40608 224.00974,683.29174 C 225.03418,680.99702 226.42742,678.93789 228.18947,677.11434 C 229.97199,675.29087 231.91843,673.93861 234.0288,673.05755 C 236.83576,671.86924 240.073,671.27506 243.74053,671.27501 C 250.3789,671.27506 255.68551,673.33419 259.66039,677.45241 C 263.65568,681.57071 265.65334,687.29735 265.65339,694.63233 C 265.65334,701.9059 263.67616,707.6018 259.72186,711.72006 C 255.76747,715.81784 250.48134,717.86672 243.86346,717.86672 C 237.16358,717.86672 231.83648,715.82808 227.88214,711.75079 C 223.92778,707.65303 221.95061,702.01859 221.95061,694.84747 M 231.32427,694.54013 C 231.32426,699.64188 232.50237,703.51428 234.8586,706.15733 C 237.2148,708.77991 240.20618,710.0912 243.83273,710.09119 C 247.45923,710.0912 250.43012,708.79016 252.74539,706.18806 C 255.08109,703.5655 256.24895,699.64188 256.24899,694.4172 C 256.24895,689.25403 255.11182,685.40213 252.83759,682.86147 C 250.58378,680.32089 247.58217,679.05058 243.83273,679.05054 C 240.08324,679.05058 237.06114,680.34138 234.7664,682.92294 C 232.47163,685.48408 231.32426,689.35648 231.32427,694.54013" /> + d="M 268.14279,717.09839 L 283.54018,693.5874 L 269.58725,672.04335 L 280.22098,672.04335 L 289.25658,686.51874 L 298.10777,672.04335 L 308.6493,672.04335 L 294.63491,693.92547 L 310.0323,717.09839 L 299.0605,717.09839 L 289.07218,701.5166 L 279.05312,717.09839 L 268.14279,717.09839" /> + d="M 43.451504,753.52476 C 43.451501,748.93528 44.137878,745.08337 45.510636,741.96903 C 46.535074,739.67431 47.928316,737.61518 49.690367,735.79163 C 51.472889,733.96817 53.41933,732.6159 55.529697,731.73484 C 58.336656,730.54653 61.573895,729.95235 65.241426,729.9523 C 71.879791,729.95235 77.186405,732.01148 81.161284,736.1297 C 85.156571,740.248 87.154234,745.97464 87.154281,753.30963 C 87.154234,760.58319 85.177059,766.2791 81.22275,770.39735 C 77.26836,774.49513 71.982235,776.54401 65.364359,776.54401 C 58.664478,776.54401 53.337375,774.50537 49.383034,770.42808 C 45.428676,766.33032 43.451501,760.69588 43.451504,753.52476 M 52.825165,753.21743 C 52.825153,758.31917 54.003263,762.19157 56.359497,764.83462 C 58.7157,767.4572 61.707073,768.76849 65.333625,768.76848 C 68.960129,768.76849 71.931013,767.46745 74.246287,764.86535 C 76.581984,762.24279 77.749849,758.31917 77.749886,753.09449 C 77.749849,747.93132 76.612717,744.07942 74.338487,741.53877 C 72.084679,738.99818 69.083062,737.72787 65.333625,737.72783 C 61.58414,737.72787 58.562033,739.01867 56.267297,741.60023 C 53.972529,744.16137 52.825153,748.03377 52.825165,753.21743" /> + d="M 94.222943,775.77568 L 94.222943,730.72064 L 108.82127,730.72064 C 114.35324,730.72068 117.95928,730.94606 119.6394,731.39677 C 122.22096,732.07295 124.38254,733.54815 126.12413,735.82237 C 127.86564,738.07618 128.73642,740.99584 128.73646,744.58136 C 128.73642,747.34739 128.23444,749.67288 127.23053,751.55783 C 126.22653,753.44283 124.94598,754.92827 123.38886,756.01416 C 121.85216,757.0796 120.28477,757.78646 118.68666,758.13476 C 116.51482,758.56504 113.36978,758.78017 109.25154,758.78016 L 103.32001,758.78016 L 103.32001,775.77568 L 94.222943,775.77568 M 103.32001,738.3425 L 103.32001,751.12756 L 108.2988,751.12756 C 111.88433,751.12758 114.28153,750.89196 115.4904,750.42069 C 116.69922,749.94948 117.6417,749.21188 118.31786,748.2079 C 119.01446,747.20397 119.36277,746.0361 119.3628,744.7043 C 119.36277,743.06522 118.88128,741.71295 117.91833,740.6475 C 116.95533,739.58211 115.73624,738.91623 114.26107,738.64983 C 113.17513,738.44498 110.99307,738.34254 107.71487,738.3425 L 103.32001,738.3425" /> + d="M 157.22624,759.21042 L 157.22624,751.61929 L 176.8341,751.61929 L 176.8341,769.56755 C 174.92859,771.41155 172.1626,773.04042 168.5361,774.45415 C 164.93003,775.84739 161.27277,776.54401 157.56431,776.54401 C 152.85185,776.54401 148.74383,775.56055 145.24025,773.59362 C 141.73664,771.6062 139.10382,768.77874 137.34179,765.11122 C 135.57974,761.42324 134.69872,757.41766 134.69872,753.09449 C 134.69872,748.40257 135.68218,744.23308 137.64912,740.58603 C 139.61605,736.93905 142.49473,734.14232 146.28518,732.19584 C 149.1741,730.70019 152.76989,729.95235 157.07258,729.9523 C 162.66601,729.95235 167.03014,731.13046 170.16497,733.48664 C 173.32022,735.82241 175.34861,739.05965 176.25017,743.19836 L 167.21457,744.8887 C 166.57938,742.67593 165.38078,740.93438 163.61877,739.66403 C 161.87719,738.37327 159.69513,737.72787 157.07258,737.72783 C 153.09771,737.72787 149.93219,738.98794 147.57598,741.50803 C 145.24024,744.0282 144.07237,747.76741 144.07238,752.72569 C 144.07237,758.07331 145.26073,762.08912 147.63745,764.77315 C 150.01414,767.43672 153.12845,768.76849 156.98038,768.76848 C 158.88582,768.76849 160.79128,768.39969 162.69677,767.66208 C 164.6227,766.90401 166.27205,765.99225 167.64484,764.92682 L 167.64484,759.21042 L 157.22624,759.21042" /> + d="M 185.19356,775.77568 L 185.19356,730.72064 L 199.79188,730.72064 C 205.32386,730.72068 208.9299,730.94606 210.61001,731.39677 C 213.19158,732.07295 215.35315,733.54815 217.09474,735.82237 C 218.83626,738.07618 219.70703,740.99584 219.70707,744.58136 C 219.70703,747.34739 219.20506,749.67288 218.20114,751.55783 C 217.19715,753.44283 215.9166,754.92827 214.35948,756.01416 C 212.82278,757.0796 211.25538,757.78646 209.65728,758.13476 C 207.48543,758.56504 204.34039,758.78017 200.22215,758.78016 L 194.29062,758.78016 L 194.29062,775.77568 L 185.19356,775.77568 M 194.29062,738.3425 L 194.29062,751.12756 L 199.26942,751.12756 C 202.85495,751.12758 205.25215,750.89196 206.46101,750.42069 C 207.66983,749.94948 208.61232,749.21188 209.28848,748.2079 C 209.98507,747.20397 210.33338,746.0361 210.33341,744.7043 C 210.33338,743.06522 209.85189,741.71295 208.88895,740.6475 C 207.92594,739.58211 206.70685,738.91623 205.23168,738.64983 C 204.14575,738.44498 201.96368,738.34254 198.68548,738.3425 L 194.29062,738.3425" /> + d="M 224.93174,761.11589 L 233.78294,760.25536 C 234.31564,763.22626 235.3913,765.40832 237.00994,766.80155 C 238.64903,768.1948 240.85158,768.89142 243.6176,768.89142 C 246.54748,768.89142 248.75004,768.27676 250.22526,767.04742 C 251.72092,765.79761 252.46876,764.3429 252.46879,762.68329 C 252.46876,761.61788 252.15119,760.71637 251.51606,759.97876 C 250.90137,759.22068 249.81546,758.56504 248.25833,758.01182 C 247.19288,757.64304 244.76495,756.9874 240.97453,756.04489 C 236.09817,754.83607 232.67653,753.35063 230.70961,751.58856 C 227.9436,749.10943 226.5606,746.08733 226.56061,742.52223 C 226.5606,740.22751 227.206,738.08643 228.49681,736.09897 C 229.80809,734.0911 231.68282,732.56468 234.121,731.5197 C 236.57966,730.47482 239.5403,729.95235 243.00293,729.9523 C 248.65784,729.95235 252.90928,731.19193 255.75726,733.67104 C 258.62567,736.15023 260.1316,739.45918 260.27506,743.5979 L 251.178,743.99743 C 250.78868,741.68222 249.94864,740.02262 248.65786,739.01863 C 247.38753,737.99423 245.47182,737.48201 242.91073,737.48197 C 240.26765,737.48201 238.19828,738.02496 236.7026,739.11083 C 235.73961,739.80749 235.25812,740.73973 235.25814,741.90757 C 235.25812,742.97302 235.70888,743.88477 236.6104,744.64283 C 237.75776,745.60584 240.54425,746.60979 244.96987,747.6547 C 249.39544,748.69966 252.66341,749.78556 254.77379,750.91243 C 256.9046,752.01885 258.5642,753.54527 259.75259,755.49169 C 260.9614,757.41766 261.56582,759.80462 261.56586,762.65255 C 261.56582,765.23416 260.84871,767.65185 259.41452,769.90562 C 257.98027,772.1594 255.95187,773.83948 253.32933,774.94588 C 250.70672,776.03179 247.43875,776.57475 243.5254,776.57475 C 237.82948,776.57475 233.4551,775.26346 230.40227,772.64088 C 227.34943,769.99782 225.52592,766.15616 224.93174,761.11589" /> + d="M 298.23071,775.77568 L 282.12645,730.72064 L 291.99185,730.72064 L 303.39391,764.06629 L 314.42717,730.72064 L 324.07743,730.72064 L 307.94244,775.77568 L 298.23071,775.77568" /> + d="M 334.2809,751.46563 C 332.0476,750.52316 330.41874,749.23237 329.3943,747.59323 C 328.39034,745.93366 327.88836,744.1204 327.88837,742.15343 C 327.88836,738.79329 329.05623,736.01705 331.39197,733.8247 C 333.74818,731.63244 337.08786,730.53628 341.41103,730.53624 C 345.69318,730.53628 349.01238,731.63244 351.36862,733.8247 C 353.7453,736.01705 354.93366,738.79329 354.93369,742.15343 C 354.93366,744.24333 354.3907,746.10781 353.30482,747.7469 C 352.21888,749.36554 350.69246,750.60512 348.72556,751.46563 C 351.22517,752.46961 353.12039,753.93456 354.41122,755.86049 C 355.72248,757.78646 356.37812,760.0095 356.37815,762.52962 C 356.37812,766.68887 355.04634,770.06953 352.38282,772.67162 C 349.73973,775.2737 346.21565,776.57475 341.81056,776.57475 C 337.71277,776.57475 334.30138,775.49908 331.57637,773.34775 C 328.35961,770.80713 326.75123,767.32403 326.75123,762.89842 C 326.75123,760.46026 327.35565,758.22697 328.5645,756.19856 C 329.77334,754.14969 331.6788,752.57205 334.2809,751.46563 M 336.06343,742.7681 C 336.06342,744.48919 336.54491,745.83122 337.5079,746.79416 C 338.49135,747.75717 339.79239,748.23866 341.41103,748.23863 C 343.05012,748.23866 344.36141,747.75717 345.34489,746.79416 C 346.32834,745.81073 346.82007,744.45846 346.82009,742.73736 C 346.82007,741.11878 346.32834,739.82798 345.34489,738.86497 C 344.38189,737.88154 343.10134,737.38981 341.50323,737.38977 C 339.84361,737.38981 338.52208,737.88154 337.53863,738.86497 C 336.55515,739.84847 336.06342,741.14951 336.06343,742.7681 M 335.26436,762.06862 C 335.26435,764.44534 335.86877,766.29958 337.07763,767.63135 C 338.30695,768.96314 339.83337,769.62902 341.65689,769.62902 C 343.43941,769.62902 344.9146,768.99387 346.08249,767.72355 C 347.25033,766.43276 347.83427,764.57852 347.83429,762.16082 C 347.83427,760.05048 347.24009,758.36015 346.05176,757.08982 C 344.86338,755.79904 343.35745,755.15365 341.53396,755.15362 C 339.42359,755.15365 337.84595,755.881 336.80103,757.33569 C 335.77657,758.79042 335.26435,760.36806 335.26436,762.06862" /> + d="M -12.73456,572.3067 A 23.877298,23.877298 0 1 1 -60.489157,572.3067 A 23.877298,23.877298 0 1 1 -12.73456,572.3067 z" + transform="matrix(0,0.40146247,-0.40146247,0,770.07457,555.54549)" /> + d="M -12.73456,572.3067 A 23.877298,23.877298 0 1 1 -60.489157,572.3067 A 23.877298,23.877298 0 1 1 -12.73456,572.3067 z" + transform="matrix(0,0.40146247,-0.40146247,0,966.79118,752.26239)" /> + d="M 54.226135,593.00714 L 54.226135,578.69073 L 58.864807,578.69073 C 60.622612,578.69075 61.768444,578.76233 62.302307,578.90558 C 63.122609,579.12044 63.809458,579.58919 64.362854,580.31183 C 64.916227,581.02799 65.19292,581.95572 65.192932,583.09503 C 65.19292,583.97395 65.033415,584.71288 64.714417,585.31183 C 64.395394,585.91079 63.988494,586.3828 63.493713,586.72784 C 63.005422,587.06639 62.507376,587.291 61.999573,587.40167 C 61.30946,587.5384 60.310112,587.60676 59.001526,587.60675 L 57.11676,587.60675 L 57.11676,593.00714 L 54.226135,593.00714 M 57.11676,581.11261 L 57.11676,585.17511 L 58.698792,585.17511 C 59.838107,585.17512 60.599825,585.10021 60.983948,584.9505 C 61.368054,584.80077 61.667533,584.56639 61.882385,584.24738 C 62.10373,583.92837 62.214407,583.55728 62.214417,583.13409 C 62.214407,582.61327 62.061412,582.18358 61.755432,581.84503 C 61.449434,581.5065 61.062064,581.29491 60.593323,581.21027 C 60.248263,581.14517 59.554905,581.11257 58.513245,581.11257 L 57.11676,581.11257" /> + d="M 66.931213,587.67511 C 66.931213,586.76366 67.155822,585.8815 67.605042,585.02863 C 68.054258,584.17577 68.689023,583.52473 69.509338,583.0755 C 70.336157,582.62629 71.25738,582.40168 72.27301,582.40167 C 73.842013,582.40168 75.127819,582.91275 76.130432,583.93488 C 77.133025,584.95051 77.634327,586.23631 77.634338,587.7923 C 77.634327,589.36131 77.126515,590.66339 76.110901,591.69855 C 75.101777,592.72719 73.828992,593.24152 72.292542,593.24152 C 71.342015,593.24152 70.433813,593.02667 69.567932,592.59698 C 68.708555,592.1673 68.054258,591.53904 67.605042,590.71222 C 67.155822,589.87889 66.931213,588.86652 66.931213,587.67511 M 69.743713,587.82159 C 69.74371,588.85024 69.98785,589.638 70.476135,590.18488 C 70.964412,590.73175 71.566625,591.00519 72.282776,591.00519 C 72.998915,591.00519 73.597873,590.73175 74.079651,590.18488 C 74.567924,589.638 74.812064,588.84373 74.812073,587.80206 C 74.812064,586.78644 74.567924,586.00519 74.079651,585.45831 C 73.597873,584.91145 72.998915,584.63801 72.282776,584.638 C 71.566625,584.63801 70.964412,584.91145 70.476135,585.45831 C 69.98785,586.00519 69.74371,586.79295 69.743713,587.82159" /> + d="M 81.726135,593.00714 L 78.444885,582.63605 L 81.110901,582.63605 L 83.05426,589.43292 L 84.84137,582.63605 L 87.487854,582.63605 L 89.21637,589.43292 L 91.198792,582.63605 L 93.90387,582.63605 L 90.573792,593.00714 L 87.937073,593.00714 L 86.149963,586.33722 L 84.392151,593.00714 L 81.726135,593.00714" /> + d="M 101.4234,589.70636 L 104.15778,590.16534 C 103.8062,591.16795 103.24956,591.93292 102.48785,592.46027 C 101.73264,592.9811 100.78537,593.24152 99.646057,593.24152 C 97.842668,593.24152 96.508034,592.65232 95.642151,591.47394 C 94.958556,590.52993 94.61676,589.33852 94.61676,587.89972 C 94.61676,586.18098 95.065978,584.83658 95.964417,583.86652 C 96.862851,582.88996 97.998918,582.40168 99.37262,582.40167 C 100.91558,582.40168 102.13303,582.91275 103.02496,583.93488 C 103.91688,584.95051 104.34331,586.50975 104.30426,588.61261 L 97.42926,588.61261 C 97.44879,589.42642 97.670142,590.06118 98.093323,590.51691 C 98.516495,590.96613 99.043839,591.19074 99.675354,591.19073 C 100.10504,591.19074 100.46636,591.07355 100.75934,590.83917 C 101.0523,590.6048 101.27365,590.2272 101.4234,589.70636 M 101.57965,586.93292 C 101.56015,586.13866 101.35503,585.53645 100.96442,585.12628 C 100.57378,584.70962 100.09852,584.50129 99.538635,584.50128 C 98.939672,584.50129 98.444881,584.71939 98.05426,585.15558 C 97.663632,585.59178 97.471574,586.18423 97.478088,586.93292 L 101.57965,586.93292" /> + d="M 109.17731,593.00714 L 106.43317,593.00714 L 106.43317,582.63605 L 108.98199,582.63605 L 108.98199,584.11066 C 109.41819,583.41405 109.80881,582.95507 110.15387,582.7337 C 110.50543,582.51236 110.90256,582.40168 111.34528,582.40167 C 111.97027,582.40168 112.57248,582.57421 113.15192,582.91925 L 112.30231,585.31183 C 111.84006,585.01236 111.41037,584.86262 111.01324,584.86261 C 110.62912,584.86262 110.3036,584.97004 110.03668,585.18488 C 109.76975,585.39322 109.55816,585.77408 109.40192,586.32745 C 109.25217,586.88085 109.1773,588.0397 109.17731,589.80402 L 109.17731,593.00714" /> + d="M 141.1961,587.99147 L 143.60567,587.75721 C 143.75068,588.56597 144.04351,589.15999 144.48415,589.53928 C 144.93036,589.91856 145.52996,590.1082 146.28296,590.1082 C 147.08056,590.1082 147.68016,589.94087 148.08176,589.60621 C 148.48892,589.26597 148.69251,588.86996 148.69252,588.41816 C 148.69251,588.12813 148.60602,587.88271 148.43316,587.68191 C 148.26582,587.47554 147.9702,587.29705 147.5463,587.14645 C 147.25625,587.04606 146.5953,586.86757 145.56344,586.61099 C 144.23594,586.28191 143.30447,585.87753 142.76901,585.39784 C 142.01602,584.72295 141.63953,583.90025 141.63953,582.92971 C 141.63953,582.30503 141.81523,581.72216 142.16662,581.18111 C 142.52359,580.63451 143.03395,580.21898 143.6977,579.9345 C 144.36702,579.65005 145.17299,579.50782 146.11563,579.5078 C 147.65506,579.50782 148.81243,579.84527 149.58773,580.52015 C 150.3686,581.19507 150.77856,582.09586 150.81762,583.22255 L 148.34112,583.33131 C 148.23514,582.70104 148.00645,582.24925 147.65506,581.97593 C 147.30924,581.69706 146.78773,581.55761 146.09052,581.5576 C 145.371,581.55761 144.80765,581.70543 144.40049,582.00103 C 144.13833,582.19069 144.00726,582.44447 144.00726,582.76239 C 144.00726,583.05243 144.12997,583.30064 144.37539,583.50701 C 144.68774,583.76917 145.4463,584.04247 146.65108,584.32693 C 147.85586,584.61139 148.7455,584.90702 149.32,585.21378 C 149.90008,585.51498 150.35187,585.93052 150.67538,586.4604 C 151.00446,586.9847 151.169,587.6345 151.16901,588.4098 C 151.169,589.11259 150.97378,589.77075 150.58335,590.3843 C 150.1929,590.99784 149.64071,591.45522 148.92678,591.75641 C 148.21283,592.05202 147.32319,592.19984 146.25785,592.19984 C 144.70725,592.19984 143.51642,591.84286 142.68535,591.12892 C 141.85427,590.4094 141.35786,589.36358 141.1961,587.99147" /> + d="M 156.02996,591.9823 L 156.02996,581.79187 L 152.39053,581.79187 L 152.39053,579.71697 L 162.13753,579.71697 L 162.13753,581.79187 L 158.50646,581.79187 L 158.50646,591.9823 L 156.02996,591.9823" /> + d="M 173.49928,591.9823 L 170.80526,591.9823 L 169.73434,589.19625 L 164.83155,589.19625 L 163.8192,591.9823 L 161.19211,591.9823 L 165.96941,579.71697 L 168.58813,579.71697 L 173.49928,591.9823 M 168.93952,587.12972 L 167.24949,582.57832 L 165.59291,587.12972 L 168.93952,587.12972" /> + d="M 176.3439,591.9823 L 176.3439,581.79187 L 172.70446,581.79187 L 172.70446,579.71697 L 182.45147,579.71697 L 182.45147,581.79187 L 178.8204,581.79187 L 178.8204,591.9823 L 176.3439,591.9823" /> + d="M 184.00764,579.71697 L 186.48414,579.71697 L 186.48414,586.35999 C 186.48413,587.41419 186.51484,588.09745 186.57614,588.4098 C 186.68211,588.91179 186.9331,589.31618 187.32913,589.62294 C 187.73071,589.92414 188.27733,590.07474 188.96897,590.07474 C 189.67175,590.07474 190.20163,589.93251 190.55861,589.64804 C 190.91558,589.358 191.13032,589.00382 191.20283,588.5855 C 191.27533,588.16717 191.31158,587.47275 191.31159,586.50223 L 191.31159,579.71697 L 193.78809,579.71697 L 193.78809,586.1592 C 193.78808,587.63171 193.72119,588.67195 193.58729,589.27991 C 193.45342,589.88788 193.20521,590.40103 192.84267,590.81936 C 192.48569,591.23768 192.00601,591.57235 191.40363,591.82334 C 190.80123,592.06876 190.01477,592.19147 189.04427,592.19147 C 187.87295,592.19147 186.98331,592.0576 186.37535,591.78987 C 185.77295,591.51657 185.29606,591.16518 184.94466,590.73569 C 184.59327,590.30063 184.36179,589.84605 184.25025,589.37195 C 184.08849,588.66916 184.00761,587.63171 184.00761,586.25959 L 184.00761,579.71697" /> - - - - - - + d="M 195.77935,587.99147 L 198.18892,587.75721 C 198.33394,588.56597 198.62676,589.15999 199.0674,589.53928 C 199.51361,589.91856 200.11321,590.1082 200.86621,590.1082 C 201.66381,590.1082 202.26341,589.94087 202.66501,589.60621 C 203.07217,589.26597 203.27576,588.86996 203.27577,588.41816 C 203.27576,588.12813 203.18927,587.88271 203.0164,587.68191 C 202.84906,587.47554 202.55345,587.29705 202.12955,587.14645 C 201.83951,587.04606 201.17854,586.86757 200.14668,586.61099 C 198.81919,586.28191 197.88771,585.87753 197.35226,585.39784 C 196.59927,584.72295 196.22278,583.90025 196.22278,582.92971 C 196.22278,582.30503 196.39847,581.72216 196.74987,581.18111 C 197.10685,580.63451 197.6172,580.21898 198.28095,579.9345 C 198.95027,579.65005 199.75624,579.50782 200.69888,579.5078 C 202.23831,579.50782 203.39568,579.84527 204.17098,580.52015 C 204.95185,581.19507 205.36181,582.09586 205.40087,583.22255 L 202.92437,583.33131 C 202.81839,582.70104 202.5897,582.24925 202.23831,581.97593 C 201.89249,581.69706 201.37098,581.55761 200.67378,581.5576 C 199.95425,581.55761 199.3909,581.70543 198.98373,582.00103 C 198.72158,582.19069 198.5905,582.44447 198.59051,582.76239 C 198.5905,583.05243 198.71321,583.30064 198.95864,583.50701 C 199.27098,583.76917 200.02955,584.04247 201.23434,584.32693 C 202.43911,584.61139 203.32875,584.90702 203.90326,585.21378 C 204.48332,585.51498 204.93512,585.93052 205.25863,586.4604 C 205.5877,586.9847 205.75225,587.6345 205.75226,588.4098 C 205.75225,589.11259 205.55703,589.77075 205.1666,590.3843 C 204.77615,590.99784 204.22396,591.45522 203.51003,591.75641 C 202.79607,592.05202 201.90643,592.19984 200.8411,592.19984 C 199.2905,592.19984 198.09967,591.84286 197.2686,591.12892 C 196.43752,590.4094 195.94111,589.36358 195.77935,587.99147" /> + + + + + style="display:none" + sodipodi:insensitive="true"> + id="nano-OPGPS-v9"> + width="42.971752" + height="7.7758408" + x="557.22125" + y="516.9964" /> + d="M 463.16123,736.88621 L 463.16123,534.74924 C 463.16123,528.07693 468.5328,522.70536 475.2051,522.70536 L 677.34317,522.70536 C 684.01547,522.70536 689.38704,528.07693 689.38704,534.74924 L 689.38704,736.88621 C 689.38704,743.55853 684.01547,748.93007 677.34317,748.93007 L 475.2051,748.93007 C 468.5328,748.93007 463.16123,743.55853 463.16123,736.88621 z" + style="fill:#eaeaea;fill-opacity:1;stroke:#ffd25c;stroke-width:4.97813463;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dashoffset:0" /> + d="M -12.73456,572.3067 A 23.877298,23.877298 0 1 1 -60.489157,572.3067 A 23.877298,23.877298 0 1 1 -12.73456,572.3067 z" + transform="matrix(0,-0.40146247,0.40146247,0,444.81646,719.53351)" /> + d="M -12.73456,572.3067 A 23.877298,23.877298 0 1 1 -60.489157,572.3067 A 23.877298,23.877298 0 1 1 -12.73456,572.3067 z" + transform="matrix(0,-0.40146247,0.40146247,0,248.09985,522.818)" /> + transform="matrix(0.64801118,0,0,0.64801118,447.52216,104.03608)"> + d="M 92.0595,965.29836 L 92.0595,963.86285 L 95.099057,963.86285 L 95.099057,967.25693 C 94.792964,967.61726 94.359019,967.92722 93.79722,968.18681 C 93.23541,968.44641 92.671669,968.5762 92.105994,968.5762 C 91.416327,968.5762 90.808029,968.40766 90.281098,968.07058 C 89.754162,967.72962 89.335715,967.22206 89.025755,966.54789 C 88.719667,965.86986 88.566624,965.07364 88.566625,964.15926 C 88.566624,963.22163 88.721605,962.4196 89.031566,961.75318 C 89.345401,961.08677 89.750287,960.5889 90.246227,960.25956 C 90.746037,959.93023 91.342711,959.76556 92.036253,959.76555 C 92.869269,959.76556 93.535685,959.97866 94.035503,960.40485 C 94.539183,960.82718 94.862705,961.44904 95.006069,962.27043 L 93.611243,962.59008 C 93.506626,962.15226 93.314838,961.81712 93.035878,961.58464 C 92.756908,961.35218 92.4237,961.23594 92.036253,961.23593 C 91.4357,961.23594 90.949449,961.47035 90.577498,961.93916 C 90.205542,962.40411 90.019566,963.11508 90.019568,964.07208 C 90.019566,965.09883 90.22104,965.87954 90.623992,966.41422 C 90.968821,966.87529 91.4357,967.10583 92.024629,967.10582 C 92.299716,967.10583 92.584492,967.04192 92.87896,966.91404 C 93.177293,966.7823 93.442697,966.60408 93.675173,966.37935 L 93.675173,965.29836 L 92.0595,965.29836" /> + d="M 96.406706,968.43091 L 96.406706,959.91085 L 98.673298,959.91085 C 99.517938,959.91086 100.07006,959.95155 100.32965,960.0329 C 100.74422,960.16464 101.08518,960.44554 101.35252,960.8756 C 101.62374,961.30568 101.75934,961.85974 101.75935,962.53777 C 101.75934,963.15382 101.64311,963.67107 101.41064,964.08951 C 101.17817,964.50409 100.88758,964.79662 100.53888,964.96709 C 100.19017,965.1337 99.589617,965.217 98.737227,965.217 L 97.813155,965.217 L 97.813155,968.43091 L 96.406706,968.43091 M 97.813155,961.35217 L 97.813155,963.76987 L 98.591933,963.76987 C 99.114989,963.76987 99.469507,963.73307 99.655487,963.65944 C 99.845334,963.58584 100.00031,963.4541 100.12043,963.26424 C 100.24053,963.07052 100.30059,962.83418 100.30059,962.55521 C 100.30059,962.27237 100.23859,962.03409 100.11462,961.84036 C 99.990629,961.64664 99.837585,961.51684 99.655487,961.45097 C 99.473381,961.38507 99.087867,961.35217 98.498944,961.35217 L 97.813155,961.35217" /> + d="M 102.56137,965.65869 L 103.93876,965.49596 C 104.09374,966.5847 104.6013,967.12907 105.46145,967.12907 C 105.88764,967.12907 106.22279,967.01865 106.46689,966.7978 C 106.71098,966.57308 106.83302,966.29605 106.83303,965.96672 C 106.83302,965.77299 106.79043,965.60833 106.70517,965.47272 C 106.61987,965.33711 106.49013,965.22669 106.31578,965.14144 C 106.14142,965.05234 105.7191,964.9051 105.04881,964.69975 C 104.44826,964.51765 104.0085,964.32005 103.72954,964.10695 C 103.45057,963.89386 103.22779,963.61489 103.06119,963.27005 C 102.89846,962.92135 102.81709,962.54746 102.81709,962.14838 C 102.81709,961.68345 102.9217,961.265 103.13093,960.89304 C 103.34402,960.52109 103.63655,960.24019 104.00851,960.05033 C 104.38046,959.86049 104.83959,959.76556 105.3859,959.76555 C 106.20729,959.76556 106.84852,959.98835 107.30959,960.43391 C 107.77065,960.87949 108.01475,961.51684 108.04188,962.34598 L 106.62961,962.42158 C 106.56761,961.96439 106.43395,961.64474 106.2286,961.46263 C 106.02325,961.28054 105.73072,961.18949 105.35102,961.18948 C 104.97132,961.18949 104.67879,961.26888 104.47345,961.42776 C 104.2681,961.58662 104.16542,961.78422 104.16542,962.02056 C 104.16542,962.25304 104.25842,962.4487 104.44439,962.60755 C 104.63036,962.76641 105.0585,962.94077 105.72879,963.13061 C 106.43782,963.33597 106.94926,963.55294 107.2631,963.78153 C 107.5808,964.00626 107.82296,964.29878 107.98957,964.65911 C 108.15617,965.01557 108.23947,965.44951 108.23948,965.96094 C 108.23947,966.70098 108.01087,967.32284 107.55369,967.82652 C 107.10036,968.33021 106.38939,968.58205 105.42077,968.58205 C 103.70823,968.58205 102.7551,967.60761 102.56137,965.65873" /> + d="M 147.50381,968.43091 L 147.50381,959.91085 L 149.7704,959.91085 C 150.61505,959.91086 151.16716,959.95155 151.42676,960.0329 C 151.84133,960.16464 152.18228,960.44554 152.44963,960.8756 C 152.72084,961.30568 152.85645,961.85974 152.85646,962.53777 C 152.85645,963.15382 152.74021,963.67107 152.50775,964.08951 C 152.27527,964.50409 151.98468,964.79662 151.63598,964.96709 C 151.28727,965.1337 150.68672,965.217 149.83433,965.217 L 148.91026,965.217 L 148.91026,968.43091 L 147.50381,968.43091 M 148.91026,961.35217 L 148.91026,963.76987 L 149.68904,963.76987 C 150.2121,963.76987 150.56661,963.73307 150.75259,963.65944 C 150.94244,963.58584 151.09742,963.4541 151.21754,963.26424 C 151.33764,963.07052 151.3977,962.83418 151.3977,962.55521 C 151.3977,962.27237 151.3357,962.03409 151.21172,961.84036 C 151.08774,961.64664 150.93469,961.51684 150.75259,961.45097 C 150.57049,961.38507 150.18497,961.35217 149.59605,961.35217 L 148.91026,961.35217" /> + d="M 153.69335,965.25768 C 153.69335,964.65326 153.81346,964.10308 154.05368,963.60714 C 154.2939,963.1112 154.60774,962.73925 154.99519,962.49128 C 155.38264,962.24331 155.81852,962.11933 156.30284,962.11932 C 157.11648,962.11933 157.75578,962.43898 158.22072,963.07827 C 158.68566,963.71369 158.91813,964.4576 158.91814,965.30999 C 158.91813,965.94541 158.79608,966.51884 158.55199,967.03027 C 158.31177,967.54171 157.99406,967.92722 157.59886,968.18681 C 157.20753,968.44253 156.77746,968.57039 156.30865,968.57039 C 155.55699,968.57039 154.93319,968.28368 154.43726,967.71025 C 153.94132,967.13682 153.69335,966.3193 153.69335,965.25768 M 155.06493,965.34488 C 155.06493,965.96868 155.18698,966.44137 155.43107,966.76295 C 155.67516,967.08066 155.96963,967.23952 156.31446,967.23951 C 156.65154,967.23952 156.94019,967.07872 157.18042,966.75714 C 157.42063,966.43555 157.54074,965.96093 157.54075,965.33325 C 157.54074,964.72108 157.41869,964.25421 157.1746,963.93262 C 156.93051,963.61104 156.63798,963.45024 156.29703,963.45024 C 155.95994,963.45024 155.66935,963.61104 155.42526,963.93262 C 155.18504,964.25421 155.06493,964.72496 155.06493,965.34488" /> + d="M 160.92901,968.43091 L 159.32496,962.25881 L 160.6268,962.25881 L 161.57412,966.3038 L 162.44588,962.25881 L 163.73609,962.25881 L 164.5788,966.3038 L 165.54937,962.25881 L 166.86864,962.25881 L 165.24134,968.43091 L 163.95694,968.43091 L 163.08518,964.46147 L 162.22503,968.43091 L 160.92901,968.43091" /> + d="M 170.51843,966.46653 L 171.84933,966.73968 C 171.6711,967.35961 171.39407,967.82067 171.01825,968.12288 C 170.64241,968.42122 170.18522,968.57039 169.64667,968.57039 C 168.89888,968.57039 168.32158,968.32048 167.91476,967.82067 C 167.43432,967.2395 167.1941,966.42585 167.1941,965.37973 C 167.1941,964.34911 167.43626,963.52384 167.92057,962.90391 C 168.33127,962.38086 168.86208,962.11933 169.513,962.11932 C 170.23753,962.11933 170.80514,962.38667 171.21585,962.92135 C 171.68853,963.53353 171.92488,964.43629 171.92488,965.62963 L 171.91888,965.81561 L 168.56549,965.81561 C 168.57349,966.3038 168.68172,966.68157 168.89095,966.94891 C 169.10404,967.21625 169.35976,967.34992 169.6581,967.34992 C 170.08817,967.34992 170.37488,967.05546 170.51824,966.46653 M 170.59384,964.81599 C 170.58224,964.33555 170.47954,963.97522 170.28581,963.735 C 170.09208,963.49091 169.86155,963.36886 169.59421,963.36885 C 169.31137,963.36886 169.07309,963.49478 168.87936,963.74662 C 168.68176,964.00234 168.5849,964.3588 168.58878,964.81599 L 170.59384,964.81599" /> + d="M 174.30771,968.43091 L 172.96519,968.43091 L 172.96519,962.25881 L 174.20891,962.25881 L 174.20891,963.13638 C 174.42201,962.72569 174.61186,962.45447 174.77846,962.32274 C 174.94894,962.18713 175.1446,962.11933 175.36545,962.11932 C 175.67154,962.11933 175.96406,962.222 176.24303,962.42735 L 175.82458,963.85123 C 175.60373,963.67301 175.39451,963.58389 175.19691,963.58389 C 175.01093,963.58389 174.84626,963.65359 174.70291,963.79311 C 174.56343,963.92873 174.46269,964.17669 174.4007,964.53702 C 174.3387,964.89735 174.3077,965.5599 174.3077,966.52465 L 174.3077,968.43091" /> + d="M 212.15979,968.43091 L 212.15979,959.91085 L 214.26946,959.91085 L 215.53643,965.72262 L 216.79177,959.91085 L 218.90725,959.91085 L 218.90725,968.43091 L 217.59961,968.43091 L 217.59961,961.72412 L 216.21059,968.43091 L 214.85064,968.43091 L 213.47325,961.72412 L 213.47325,968.43091 L 212.15979,968.43091" /> + d="M 224.78876,965.29836 L 226.15453,965.82723 C 225.94142,966.78037 225.58691,967.47778 225.09097,967.91947 C 224.59503,968.35729 223.9848,968.5762 223.26027,968.5762 C 222.34975,968.5762 221.61166,968.22556 221.04598,967.52427 C 220.39506,966.7145 220.0696,965.62189 220.0696,964.24643 C 220.0696,962.79349 220.397,961.65633 221.05179,960.83492 C 221.62134,960.12202 222.38656,959.76556 223.34744,959.76555 C 224.13009,959.76556 224.78488,960.0329 225.31182,960.56758 C 225.68764,960.94729 225.96273,961.51103 226.13709,962.25881 L 224.74227,962.66563 C 224.65317,962.20457 224.47492,961.85199 224.20758,961.60789 C 223.94411,961.35993 223.63221,961.23594 223.27189,961.23593 C 222.75657,961.23594 222.33619,961.46066 222.01073,961.9101 C 221.68527,962.35955 221.52254,963.10152 221.52255,964.13601 C 221.52254,965.20925 221.6814,965.97253 221.99911,966.42585 C 222.31682,966.87917 222.72945,967.10583 223.23702,967.10582 C 223.60897,967.10583 223.93055,966.96247 224.20177,966.67575 C 224.47298,966.38517 224.66865,965.92604 224.78876,965.29836" /> + d="M 227.34594,959.91085 L 228.75239,959.91085 L 228.75239,964.5254 C 228.75239,965.24219 228.76979,965.70906 228.80469,965.92603 C 228.86669,966.30186 229.01391,966.59245 229.24638,966.7978 C 229.48272,967.00315 229.79268,967.10583 230.17627,967.10582 C 230.50172,967.10583 230.76712,967.03412 230.97248,966.89079 C 231.17782,966.74356 231.31731,966.54208 231.39093,966.28636 C 231.46843,966.02677 231.50716,965.47272 231.50716,964.6242 L 231.50716,959.91085 L 232.91942,959.91085 L 232.91942,964.38591 C 232.91942,965.5289 232.85742,966.35611 232.73345,966.86754 C 232.61333,967.3751 232.33824,967.78774 231.90817,968.10545 C 231.48197,968.41928 230.91823,968.5762 230.21695,968.5762 C 229.48854,968.5762 228.91898,968.44641 228.50829,968.18681 C 228.10146,967.92335 227.80506,967.55527 227.61909,967.08258 C 227.43698,966.60601 227.34593,965.73037 227.34593,964.45566 L 227.34593,959.91085" /> + transform="matrix(1.5711089,0,0,1.5372108,223.37514,520.91932)" /> + points="186.083,4.74 191.036,13.319 186.194,11.031 181.129,13.319 " /> + transform="matrix(0.77129601,0,0,0.77129601,406.05121,-118.91884)"> - - - - - - + + + + @@ -12836,55 +12911,54 @@ inkscape:groupmode="layer" id="layer40" inkscape:label="nano-ms4525" - style="display:none"> + style="display:none" + sodipodi:insensitive="true"> + transform="matrix(0.73908188,0,0,0.73908188,491.6837,-344.81271)"> @@ -12892,60 +12966,60 @@ + transform="matrix(0.73908188,0,0,0.73908188,491.6837,-344.81271)"> + transform="matrix(0.73908188,0,0,0.73908188,491.6837,-344.81271)"> @@ -13178,200 +13252,190 @@ inkscape:transform-center-y="43.141303" inkscape:transform-center-x="-52.764729" style="fill:#e9dcdc;display:inline" - x="462.03354" - y="-778.26166" - width="15.304846" - height="6.6888146" + x="602.16431" + y="-39.386379" + width="11.311534" + height="4.9435816" transform="scale(1,-1)" id="rect4400" /> + width="45.098602" + height="50.196705" + x="557.56689" + y="-4.3422861" + rx="0.77129602" + ry="0.77129602" /> + + + + + id="g9542-2" + style="stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" + transform="translate(225.07579,-457.5649)"> + d="M 275.76889,464.24561 L 275.76889,463.29207 L 278.23188,463.29207 L 278.23188,465.5466 C 277.99252,465.77823 277.64508,465.98283 277.18955,466.16042 C 276.73658,466.33542 276.27718,466.42293 275.81135,466.42293 C 275.21941,466.42293 274.70339,466.29939 274.2633,466.05232 C 273.8232,465.80268 273.49248,465.44751 273.27115,464.98683 C 273.04982,464.52357 272.93915,464.02042 272.93915,463.47738 C 272.93915,462.88801 273.06268,462.36427 273.30976,461.90616 C 273.55683,461.44805 273.91842,461.09675 274.39455,460.85225 C 274.75744,460.66437 275.20911,460.57044 275.74958,460.57043 C 276.45219,460.57044 277.00038,460.71842 277.39415,461.01439 C 277.79049,461.30779 278.04528,461.71443 278.15853,462.2343 L 277.02354,462.44663 C 276.94374,462.16868 276.7932,461.94992 276.57187,461.79034 C 276.3531,461.62821 276.07901,461.54714 275.74958,461.54713 C 275.25029,461.54714 274.85266,461.70542 274.55669,462.02197 C 274.26329,462.33854 274.1166,462.80823 274.1166,463.43105 C 274.1166,464.10278 274.26587,464.60721 274.56441,464.94436 C 274.86296,465.27894 275.25415,465.44623 275.738,465.44623 C 275.97735,465.44623 276.2167,465.39993 276.45605,465.30725 C 276.69797,465.21205 276.90515,465.0975 277.07759,464.96366 L 277.07759,464.24561 L 275.76889,464.24561" + style="font-size:7.9062767px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;font-family:Arial;-inkscape-font-specification:Arial Bold" + id="path8513-0" + inkscape:connector-curvature="0" /> + d="M 283.00344,466.32642 L 281.91864,466.32642 L 281.91864,464.23403 C 281.91864,463.79137 281.89544,463.50569 281.84914,463.377 C 281.80284,463.24575 281.72689,463.14409 281.62137,463.07203 C 281.51842,462.99993 281.3936,462.96394 281.24691,462.96393 C 281.05903,462.96394 280.89045,463.01543 280.74118,463.11835 C 280.59191,463.2213 280.48896,463.3577 280.43234,463.52756 C 280.37834,463.69743 280.35124,464.01141 280.35124,464.46952 L 280.35124,466.32642 L 279.26645,466.32642 L 279.26645,462.22658 L 280.27403,462.22658 L 280.27403,462.82882 C 280.63177,462.36556 281.08216,462.13393 281.6252,462.13393 C 281.86455,462.13393 282.08331,462.17763 282.28149,462.26518 C 282.47966,462.35008 282.62893,462.4595 282.7293,462.59333 C 282.83225,462.72716 282.90302,462.879 282.94163,463.04886 C 282.98283,463.21873 283.00343,463.46194 283.00343,463.77849 L 283.00343,466.32642" + style="font-size:7.9062767px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;font-family:Arial;-inkscape-font-specification:Arial Bold" + id="path8515-7" + inkscape:connector-curvature="0" /> - + d="M 287.86765,466.32642 L 286.86006,466.32642 L 286.86006,465.72418 C 286.69277,465.95838 286.4946,466.13339 286.26555,466.24921 C 286.03906,466.36245 285.81001,466.41907 285.57838,466.41907 C 285.1074,466.41907 284.70334,466.2299 284.36619,465.85158 C 284.03161,465.47068 283.86433,464.9405 283.86433,464.26106 C 283.86433,463.56617 284.02775,463.03857 284.35461,462.67826 C 284.68146,462.31537 285.09453,462.13393 285.59382,462.13393 C 286.05193,462.13393 286.44828,462.32438 286.78285,462.70528 L 286.78285,460.66694 L 287.86765,460.66694 L 287.86765,466.32642 M 284.97229,464.18771 C 284.97228,464.62523 285.03279,464.94179 285.15373,465.13739 C 285.32874,465.42049 285.57323,465.56204 285.88722,465.56204 C 286.13686,465.56204 286.34919,465.45652 286.5242,465.24548 C 286.69921,465.03187 286.78671,464.71402 286.78672,464.29194 C 286.78671,463.82096 286.70182,463.48253 286.53192,463.27663 C 286.36206,463.06817 286.14458,462.96394 285.8795,462.96393 C 285.62213,462.96394 285.40595,463.06688 285.23094,463.27277 C 285.0585,463.47609 284.97228,463.78107 284.97229,464.18771" + style="font-size:7.9062767px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;font-family:Arial;-inkscape-font-specification:Arial Bold" + id="path8517-0" + inkscape:connector-curvature="0" /> - - - - - - - - - - - - - - - - - - - - + id="g9527-4" + style="fill:#1f4697;fill-opacity:1;stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" + transform="translate(225.07579,-457.5649)"> + + + + + + + + + + + + + + transform="matrix(0.25567841,0,0,0.25567841,399.83811,-87.969319)"> + points="251.619,492.937 251.619,485.734 242.74,485.734 242.74,480.095 251.619,480.095 251.619,473.728 242.74,473.728 242.74,467.777 251.619,467.777 251.619,467.777 251.619,460.783 233.13,460.783 233.13,492.937 " /> + points="253.082,454.937 220.283,454.937 220.283,364.946 220.283,364.946 253.082,364.946 " /> + points="247.754,449.298 247.754,370.688 225.505,370.688 225.505,370.688 225.505,449.298 " /> @@ -13380,169 +13444,170 @@ inkscape:groupmode="layer" id="layer41" inkscape:label="nano-eagletree" - style="display:inline"> + style="display:none" + sodipodi:insensitive="true"> + transform="matrix(0.77129601,0,0,0.77129601,324.31484,-384.90486)"> + style="fill:url(#linearGradient15469);fill-opacity:1;fill-rule:evenodd;stroke:#222223;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + width="6.8847327" + height="13.769465" + x="604.16449" + y="-46.039955" + rx="0.77129602" + ry="0.77129602" /> + style="fill:url(#linearGradient15465);fill-opacity:1;stroke:#222223;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + d="M 571.01776,18.4088 L 567.38415,37.91554 L 568.34036,41.357911 L 575.41634,35.238148 L 577.52001,21.659921 L 573.69516,18.791286 z" + style="fill:#df181b;fill-opacity:1;stroke:#000000;stroke-width:0.77129602px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> + d="M 576.75503,16.305129 L 582.49231,12.48028 L 599.32166,12.289037 L 604.29397,15.348915 L 604.10272,17.0701 L 599.32166,20.321221 L 580.96238,20.321221 z" + style="fill:#df181b;fill-opacity:1;stroke:#000000;stroke-width:0.77129602px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> + d="M 571.209,14.775186 L 573.8864,-4.922796 L 577.32876,-8.3651672 L 581.5361,-2.6278818 L 579.81492,11.524066 L 575.03386,14.966429 z" + style="fill:#343535;fill-opacity:1;stroke:#000000;stroke-width:0.77129602px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> + d="M 580.00616,-8.938888 L 584.02225,-3.5840961 L 603.91148,-3.5840961 L 610.03124,-8.938888 L 610.41373,-11.233802 L 580.38865,-11.042559 z" + style="fill:#df181b;fill-opacity:1;stroke:#000000;stroke-width:0.77129602;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /> + d="M 611.1787,-6.6439816 L 604.67645,-1.8629182 L 602.76403,10.185366 L 605.25018,14.010215 L 610.03124,13.627729 L 612.89989,-6.2614959 z" + style="fill:#df181b;fill-opacity:1;stroke:#000000;stroke-width:0.77129602px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> + d="M 601.61657,21.086192 L 606.97136,16.878858 L 608.9849,17.0701 L 605.73377,38.738983 L 603.04055,40.019211 L 599.32166,35.42939 z" + style="fill:#343535;fill-opacity:1;stroke:#000000;stroke-width:0.77129602px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> + d="M 576.5638,37.341811 L 597.40924,37.341811 L 601.42533,41.740389 L 600.66036,44.417789 L 571.01776,44.226546 L 570.06155,43.079089 z" + style="fill:#df181b;fill-opacity:1;stroke:#000000;stroke-width:0.77129602px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> + style="fill:#18181b;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + width="39.395973" + height="17.785559" + x="728.01526" + y="19.859884" + rx="2.3138881" + ry="2.3138883" /> + width="39.395973" + height="17.785559" + x="728.01526" + y="-20.247509" + rx="2.3138881" + ry="2.3138883" /> + style="fill:url(#linearGradient15449);fill-opacity:1;fill-rule:evenodd;stroke:none" /> + style="fill:#2f3430;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + style="fill:#949697;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + style="fill:#18181b;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + width="4.7210732" + height="19.506727" + x="581.00055" + y="-49.482307" + rx="0.77129602" + ry="0.77129602" /> + transform="matrix(0.93020998,0,0,0.93020998,125.80214,-282.07461)"> + transform="matrix(0,0.77129601,-0.77129601,0,596.02836,-372.22641)"> @@ -14068,102 +14133,102 @@ inkscape:transform-center-y="39.602712" inkscape:transform-center-x="3.4283597" style="fill:#e9dcdc" - x="-398.08838" - y="-509.16299" - width="7.6110497" - height="4.0624456" + x="-631.35883" + y="-46.375324" + width="5.8703723" + height="3.1333482" transform="scale(-1,-1)" id="rect6483" /> @@ -14171,19 +14236,19 @@ inkscape:transform-center-y="167.71085" inkscape:transform-center-x="15.713991" style="fill:#8c8c8c;fill-opacity:1" - x="-295.85876" - y="-483.67529" - width="34.885509" - height="17.203777" + x="-552.50952" + y="-26.716764" + width="26.907055" + height="13.269205" transform="scale(-1,-1)" id="rect6511" /> @@ -14191,123 +14256,123 @@ inkscape:transform-center-y="167.71085" inkscape:transform-center-x="15.713991" style="fill:#8c8c8c;fill-opacity:1" - x="-295.85876" - y="-435.67529" - width="34.885509" - height="17.203777" + x="-552.50952" + y="10.305445" + width="26.907055" + height="13.269205" transform="scale(-1,-1)" id="rect6515" /> + style="opacity:0.87969923;fill:#2f3430;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + width="19.124256" + height="7.0759711" + x="506.37778" + y="7.0987101" /> + width="6.8847327" + height="13.769465" + x="707.46936" + y="-20.39933" + rx="0.77129602" + ry="0.77129602" /> + style="fill:#949697;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + width="6.8847327" + height="13.769465" + x="707.46936" + y="22.793247" + rx="0.77129602" + ry="0.77129602" /> + transform="matrix(0.77129601,0,0,0.77129601,446.51805,-65.299084)"> @@ -14317,199 +14382,188 @@ + + + + + + + + + id="g9542-2-1" + style="stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" + transform="translate(157.04015,-452.49384)"> + d="M 275.76889,464.24561 L 275.76889,463.29207 L 278.23188,463.29207 L 278.23188,465.5466 C 277.99252,465.77823 277.64508,465.98283 277.18955,466.16042 C 276.73658,466.33542 276.27718,466.42293 275.81135,466.42293 C 275.21941,466.42293 274.70339,466.29939 274.2633,466.05232 C 273.8232,465.80268 273.49248,465.44751 273.27115,464.98683 C 273.04982,464.52357 272.93915,464.02042 272.93915,463.47738 C 272.93915,462.88801 273.06268,462.36427 273.30976,461.90616 C 273.55683,461.44805 273.91842,461.09675 274.39455,460.85225 C 274.75744,460.66437 275.20911,460.57044 275.74958,460.57043 C 276.45219,460.57044 277.00038,460.71842 277.39415,461.01439 C 277.79049,461.30779 278.04528,461.71443 278.15853,462.2343 L 277.02354,462.44663 C 276.94374,462.16868 276.7932,461.94992 276.57187,461.79034 C 276.3531,461.62821 276.07901,461.54714 275.74958,461.54713 C 275.25029,461.54714 274.85266,461.70542 274.55669,462.02197 C 274.26329,462.33854 274.1166,462.80823 274.1166,463.43105 C 274.1166,464.10278 274.26587,464.60721 274.56441,464.94436 C 274.86296,465.27894 275.25415,465.44623 275.738,465.44623 C 275.97735,465.44623 276.2167,465.39993 276.45605,465.30725 C 276.69797,465.21205 276.90515,465.0975 277.07759,464.96366 L 277.07759,464.24561 L 275.76889,464.24561" + style="font-size:7.9062767px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;font-family:Arial;-inkscape-font-specification:Arial Bold" + id="path8513-0-8" + inkscape:connector-curvature="0" /> + d="M 283.00344,466.32642 L 281.91864,466.32642 L 281.91864,464.23403 C 281.91864,463.79137 281.89544,463.50569 281.84914,463.377 C 281.80284,463.24575 281.72689,463.14409 281.62137,463.07203 C 281.51842,462.99993 281.3936,462.96394 281.24691,462.96393 C 281.05903,462.96394 280.89045,463.01543 280.74118,463.11835 C 280.59191,463.2213 280.48896,463.3577 280.43234,463.52756 C 280.37834,463.69743 280.35124,464.01141 280.35124,464.46952 L 280.35124,466.32642 L 279.26645,466.32642 L 279.26645,462.22658 L 280.27403,462.22658 L 280.27403,462.82882 C 280.63177,462.36556 281.08216,462.13393 281.6252,462.13393 C 281.86455,462.13393 282.08331,462.17763 282.28149,462.26518 C 282.47966,462.35008 282.62893,462.4595 282.7293,462.59333 C 282.83225,462.72716 282.90302,462.879 282.94163,463.04886 C 282.98283,463.21873 283.00343,463.46194 283.00343,463.77849 L 283.00343,466.32642" + style="font-size:7.9062767px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;font-family:Arial;-inkscape-font-specification:Arial Bold" + id="path8515-7-4" + inkscape:connector-curvature="0" /> - - - - - + d="M 287.86765,466.32642 L 286.86006,466.32642 L 286.86006,465.72418 C 286.69277,465.95838 286.4946,466.13339 286.26555,466.24921 C 286.03906,466.36245 285.81001,466.41907 285.57838,466.41907 C 285.1074,466.41907 284.70334,466.2299 284.36619,465.85158 C 284.03161,465.47068 283.86433,464.9405 283.86433,464.26106 C 283.86433,463.56617 284.02775,463.03857 284.35461,462.67826 C 284.68146,462.31537 285.09453,462.13393 285.59382,462.13393 C 286.05193,462.13393 286.44828,462.32438 286.78285,462.70528 L 286.78285,460.66694 L 287.86765,460.66694 L 287.86765,466.32642 M 284.97229,464.18771 C 284.97228,464.62523 285.03279,464.94179 285.15373,465.13739 C 285.32874,465.42049 285.57323,465.56204 285.88722,465.56204 C 286.13686,465.56204 286.34919,465.45652 286.5242,465.24548 C 286.69921,465.03187 286.78671,464.71402 286.78672,464.29194 C 286.78671,463.82096 286.70182,463.48253 286.53192,463.27663 C 286.36206,463.06817 286.14458,462.96394 285.8795,462.96393 C 285.62213,462.96394 285.40595,463.06688 285.23094,463.27277 C 285.0585,463.47609 284.97228,463.78107 284.97229,464.18771" + style="font-size:7.9062767px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;font-family:Arial;-inkscape-font-specification:Arial Bold" + id="path8517-0-9" + inkscape:connector-curvature="0" /> - - - - - - - - - - - - - - - - - - - - + id="g9532-0-9" + style="fill:#ec6004;fill-opacity:1;stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" + transform="translate(157.54014,-490.99384)"> + + + + + + + + + + + + + + transform="matrix(0.25567841,0,0,0.25567841,277.33811,-96.969324)"> + points="233.13,460.783 233.13,492.937 251.619,492.937 251.619,485.734 242.74,485.734 242.74,480.095 251.619,480.095 251.619,473.728 242.74,473.728 242.74,467.777 251.619,467.777 251.619,467.777 251.619,460.783 " /> @@ -14541,54 +14595,54 @@ inkscape:groupmode="layer" id="layer42" inkscape:label="ms4525" - style="display:none"> + style="display:none" + sodipodi:insensitive="true"> @@ -14596,57 +14650,59 @@ @@ -14880,198 +14936,188 @@ inkscape:transform-center-y="43.141303" inkscape:transform-center-x="-52.764729" style="fill:#e9dcdc;display:inline" - x="149.4836" - y="-519.83289" - width="15.304846" - height="6.6888146" + x="315.224" + y="-497.14481" + width="11.311534" + height="4.9435816" transform="scale(1,-1)" id="rect4400-7" /> - - - - - - + width="45.098602" + height="50.196705" + x="270.62656" + y="453.41617" + rx="0.77129602" + ry="0.77129602" /> + + + + - - - - - - - - - - - - - - - - - - - - + id="g9542-2-1-5" + style="stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" + transform="translate(-68.822223,-0.49726981)"> + + + + + + + + + + + + + + + + + + @@ -15079,169 +15125,170 @@ inkscape:groupmode="layer" id="layer43" inkscape:label="eagletree" - style="display:none"> + style="display:inline" + sodipodi:insensitive="true"> + transform="matrix(0.77129601,0,0,0.77129601,-4.0324,109.23554)"> + style="fill:url(#linearGradient15115);fill-opacity:1;fill-rule:evenodd;stroke:#222223;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + width="6.8847327" + height="13.769465" + x="275.81726" + y="448.10043" + rx="0.77129602" + ry="0.77129602" /> + style="fill:url(#linearGradient15111);fill-opacity:1;stroke:#222223;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + d="M 242.67052,512.5492 L 239.03691,532.05594 L 239.99312,535.49831 L 247.0691,529.37855 L 249.17277,515.80032 L 245.34792,512.93169 z" + style="fill:#df181b;fill-opacity:1;stroke:#000000;stroke-width:0.77129602px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> + d="M 248.40779,510.44553 L 254.14507,506.62068 L 270.97442,506.42944 L 275.94673,509.48931 L 275.75548,511.2105 L 270.97442,514.46162 L 252.61514,514.46162 z" + style="fill:#df181b;fill-opacity:1;stroke:#000000;stroke-width:0.77129602px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> + d="M 242.86176,508.91559 L 245.53916,489.2176 L 248.98152,485.77523 L 253.18886,491.51252 L 251.46768,505.66447 L 246.68662,509.10683 z" + style="fill:#343535;fill-opacity:1;stroke:#000000;stroke-width:0.77129602px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> + d="M 251.65892,485.20151 L 255.67501,490.5563 L 275.56424,490.5563 L 281.684,485.20151 L 282.06649,482.9066 L 252.04141,483.09784 z" + style="fill:#df181b;fill-opacity:1;stroke:#000000;stroke-width:0.77129602;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none" /> + d="M 282.83146,487.49642 L 276.32921,492.27748 L 274.41679,504.32577 L 276.90294,508.15061 L 281.684,507.76813 L 284.55265,487.8789 z" + style="fill:#df181b;fill-opacity:1;stroke:#000000;stroke-width:0.77129602px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> + d="M 273.26933,515.22659 L 278.62412,511.01926 L 280.63766,511.2105 L 277.38653,532.87938 L 274.69331,534.15961 L 270.97442,529.56979 z" + style="fill:#343535;fill-opacity:1;stroke:#000000;stroke-width:0.77129602px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> + d="M 248.21656,531.48221 L 269.062,531.48221 L 273.07809,535.88079 L 272.31312,538.55819 L 242.67052,538.36695 L 241.71431,537.21949 z" + style="fill:#df181b;fill-opacity:1;stroke:#000000;stroke-width:0.77129602px;stroke-linecap:butt;stroke-linejoin:miter;stroke-opacity:1" /> + style="fill:#18181b;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + width="39.395973" + height="17.785559" + x="399.668" + y="514.00031" + rx="2.3138881" + ry="2.3138883" /> + width="39.395973" + height="17.785559" + x="399.668" + y="473.89288" + rx="2.3138881" + ry="2.3138883" /> + style="fill:url(#linearGradient15095);fill-opacity:1;fill-rule:evenodd;stroke:none" /> + style="fill:#2f3430;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + style="fill:#949697;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + style="fill:#18181b;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + width="4.7210732" + height="19.506727" + x="252.65331" + y="444.65808" + rx="0.77129602" + ry="0.77129602" /> + transform="matrix(0.93020998,0,0,0.93020998,-202.5451,212.06579)"> + transform="matrix(0,0.77129601,-0.77129601,0,267.68112,121.91399)"> @@ -15767,102 +15814,102 @@ inkscape:transform-center-y="39.602712" inkscape:transform-center-x="3.4283597" style="fill:#e9dcdc" - x="-398.08838" - y="-509.16299" - width="7.6110497" - height="4.0624456" + x="-303.01157" + y="-540.51575" + width="5.8703723" + height="3.1333482" transform="scale(-1,-1)" id="rect6483-9" /> @@ -15870,19 +15917,19 @@ inkscape:transform-center-y="167.71085" inkscape:transform-center-x="15.713991" style="fill:#8c8c8c;fill-opacity:1" - x="-295.85876" - y="-483.67529" - width="34.885509" - height="17.203777" + x="-224.16228" + y="-520.85718" + width="26.907055" + height="13.269205" transform="scale(-1,-1)" id="rect6511-3" /> @@ -15890,123 +15937,123 @@ inkscape:transform-center-y="167.71085" inkscape:transform-center-x="15.713991" style="fill:#8c8c8c;fill-opacity:1" - x="-295.85876" - y="-435.67529" - width="34.885509" - height="17.203777" + x="-224.16228" + y="-483.83496" + width="26.907055" + height="13.269205" transform="scale(-1,-1)" id="rect6515-1" /> + style="opacity:0.87969923;fill:#2f3430;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + width="19.124256" + height="7.0759711" + x="178.03053" + y="501.23911" /> + width="6.8847327" + height="13.769465" + x="379.1221" + y="473.74106" + rx="0.77129602" + ry="0.77129602" /> + style="fill:#949697;fill-opacity:1;fill-rule:evenodd;stroke:#171600;stroke-width:0.77129602;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0" /> + width="6.8847327" + height="13.769465" + x="379.1221" + y="516.93365" + rx="0.77129602" + ry="0.77129602" /> + transform="matrix(0.77129601,0,0,0.77129601,118.17081,428.84132)"> @@ -16016,222 +16063,211 @@ + + + + + + + + + id="g9542-2-1-6" + style="stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" + transform="translate(-170.04363,41.59812)"> + d="M 275.76889,464.24561 L 275.76889,463.29207 L 278.23188,463.29207 L 278.23188,465.5466 C 277.99252,465.77823 277.64508,465.98283 277.18955,466.16042 C 276.73658,466.33542 276.27718,466.42293 275.81135,466.42293 C 275.21941,466.42293 274.70339,466.29939 274.2633,466.05232 C 273.8232,465.80268 273.49248,465.44751 273.27115,464.98683 C 273.04982,464.52357 272.93915,464.02042 272.93915,463.47738 C 272.93915,462.88801 273.06268,462.36427 273.30976,461.90616 C 273.55683,461.44805 273.91842,461.09675 274.39455,460.85225 C 274.75744,460.66437 275.20911,460.57044 275.74958,460.57043 C 276.45219,460.57044 277.00038,460.71842 277.39415,461.01439 C 277.79049,461.30779 278.04528,461.71443 278.15853,462.2343 L 277.02354,462.44663 C 276.94374,462.16868 276.7932,461.94992 276.57187,461.79034 C 276.3531,461.62821 276.07901,461.54714 275.74958,461.54713 C 275.25029,461.54714 274.85266,461.70542 274.55669,462.02197 C 274.26329,462.33854 274.1166,462.80823 274.1166,463.43105 C 274.1166,464.10278 274.26587,464.60721 274.56441,464.94436 C 274.86296,465.27894 275.25415,465.44623 275.738,465.44623 C 275.97735,465.44623 276.2167,465.39993 276.45605,465.30725 C 276.69797,465.21205 276.90515,465.0975 277.07759,464.96366 L 277.07759,464.24561 L 275.76889,464.24561" + style="font-size:7.9062767px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;font-family:Arial;-inkscape-font-specification:Arial Bold" + id="path8513-0-8-0" + inkscape:connector-curvature="0" /> + d="M 283.00344,466.32642 L 281.91864,466.32642 L 281.91864,464.23403 C 281.91864,463.79137 281.89544,463.50569 281.84914,463.377 C 281.80284,463.24575 281.72689,463.14409 281.62137,463.07203 C 281.51842,462.99993 281.3936,462.96394 281.24691,462.96393 C 281.05903,462.96394 280.89045,463.01543 280.74118,463.11835 C 280.59191,463.2213 280.48896,463.3577 280.43234,463.52756 C 280.37834,463.69743 280.35124,464.01141 280.35124,464.46952 L 280.35124,466.32642 L 279.26645,466.32642 L 279.26645,462.22658 L 280.27403,462.22658 L 280.27403,462.82882 C 280.63177,462.36556 281.08216,462.13393 281.6252,462.13393 C 281.86455,462.13393 282.08331,462.17763 282.28149,462.26518 C 282.47966,462.35008 282.62893,462.4595 282.7293,462.59333 C 282.83225,462.72716 282.90302,462.879 282.94163,463.04886 C 282.98283,463.21873 283.00343,463.46194 283.00343,463.77849 L 283.00343,466.32642" + style="font-size:7.9062767px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;font-family:Arial;-inkscape-font-specification:Arial Bold" + id="path8515-7-4-1" + inkscape:connector-curvature="0" /> - - - - - + d="M 287.86765,466.32642 L 286.86006,466.32642 L 286.86006,465.72418 C 286.69277,465.95838 286.4946,466.13339 286.26555,466.24921 C 286.03906,466.36245 285.81001,466.41907 285.57838,466.41907 C 285.1074,466.41907 284.70334,466.2299 284.36619,465.85158 C 284.03161,465.47068 283.86433,464.9405 283.86433,464.26106 C 283.86433,463.56617 284.02775,463.03857 284.35461,462.67826 C 284.68146,462.31537 285.09453,462.13393 285.59382,462.13393 C 286.05193,462.13393 286.44828,462.32438 286.78285,462.70528 L 286.78285,460.66694 L 287.86765,460.66694 L 287.86765,466.32642 M 284.97229,464.18771 C 284.97228,464.62523 285.03279,464.94179 285.15373,465.13739 C 285.32874,465.42049 285.57323,465.56204 285.88722,465.56204 C 286.13686,465.56204 286.34919,465.45652 286.5242,465.24548 C 286.69921,465.03187 286.78671,464.71402 286.78672,464.29194 C 286.78671,463.82096 286.70182,463.48253 286.53192,463.27663 C 286.36206,463.06817 286.14458,462.96394 285.8795,462.96393 C 285.62213,462.96394 285.40595,463.06688 285.23094,463.27277 C 285.0585,463.47609 284.97228,463.78107 284.97229,464.18771" + style="font-size:7.9062767px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;font-family:Arial;-inkscape-font-specification:Arial Bold" + id="path8517-0-9-9" + inkscape:connector-curvature="0" /> - - - - - - - - - - - - - - - - - - - - + id="g9532-0-9-58" + style="fill:#ec6004;fill-opacity:1;stroke:#000000;stroke-width:0.2;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;display:inline" + transform="translate(-170.54362,3.598122)"> + + + + + + + + + + + + + + transform="matrix(0.25567841,0,0,0.25567841,-50.745653,387.62262)"> + points="251.619,480.095 251.619,473.728 242.74,473.728 242.74,467.777 251.619,467.777 251.619,467.777 251.619,460.783 233.13,460.783 233.13,492.937 251.619,492.937 251.619,485.734 242.74,485.734 242.74,480.095 " /> + points="220.283,364.946 253.082,364.946 253.082,454.937 220.283,454.937 220.283,364.946 " /> + points="225.505,370.688 225.505,449.298 247.754,449.298 247.754,370.688 225.505,370.688 " /> @@ -16242,12 +16278,13 @@ id="layer11" inkscape:label="boards" style="display:inline" - transform="translate(9.5291677,71.377308)"> + transform="translate(9.5291677,71.377308)" + sodipodi:insensitive="true"> @@ -22395,7 +22432,7 @@ inkscape:groupmode="layer" id="layer18" inkscape:label="nano" - style="display:inline" + style="display:none" sodipodi:insensitive="true"> + d="M 399.52159,854.64741 C 399.52159,855.82348 398.54605,856.77798 397.34404,856.77798 H 368.00816 C 366.80616,856.77798 365.83062,855.82348 365.83062,854.64741 L 368.00816,853.21887 L 365.83062,850.95515 V 817.93144 L 368.00816,815.4014 L 365.83062,814.02931 C 365.83062,812.85324 366.80616,811.89875 368.00816,811.89875 H 397.34513 C 398.54713,811.89875 399.52267,812.85324 399.52267,814.02931 V 854.64741 z" /> @@ -22828,7 +22865,7 @@ + d="M 481.28621,675.07193 L 481.89919,676.91913 C 486.0583,675.4011 484.75177,668.65148 479.64107,670.096 C 484.01903,669.62089 484.08762,674.75874 481.28621,675.07193 z" /> + d="M 479.90129,671.06754 L 479.28831,669.22034 C 475.1292,670.73837 476.43573,677.48799 481.54751,676.04347 C 477.16956,676.51858 477.10097,671.38073 479.90129,671.06754 z" /> + d="M 468.75771,677.71276 H 467.02656 L 465.41409,674.45833 H 465.24206 V 676.67731 H 463.66334 V 669.47494 C 464.07816,669.46494 465.06023,669.31728 465.52623,669.31728 C 466.00202,669.31728 466.55947,669.33748 467.04616,669.5836 C 467.84531,669.97989 468.28082,670.81294 468.22965,672.30859 C 468.1284,673.52727 467.68309,674.11105 467.00478,674.34967 L 468.75771,677.71276 z M 466.64984,671.9709 C 466.64984,671.3573 466.42664,670.69363 465.75814,670.69363 C 465.58611,670.69363 465.39558,670.71283 465.24206,670.74263 V 673.278 C 466.21324,673.63593 466.64984,672.8636 466.64984,671.9709 z" /> + d="M 468.44196,676.67731 V 669.47494 H 471.76272 V 670.83211 H 470.06205 V 672.40766 H 471.68215 V 673.69559 H 470.06205 V 675.27114 H 471.76272 V 676.67731 H 468.44196 z" /> + d="M 474.48574,674.46792 L 475.2555,669.47494 H 476.94636 L 475.41773,676.67731 H 473.4035 L 471.86397,669.47494 H 473.56464 L 474.33549,674.46792 L 474.41609,675.07193 L 474.48579,674.46792 z" /> + d="M 484.72564,676.67731 V 669.47494 H 486.32505 V 675.27007 H 488.11717 V 676.67624 H 484.72564 z" /> + d="M 488.28919,674.69589 V 669.47494 H 489.9082 V 674.6064 C 489.9182,675.09217 489.9496,675.4778 490.61699,675.4778 C 491.2844,675.4778 491.31598,675.09217 491.32578,674.6064 V 669.47494 H 492.94478 V 674.69589 C 492.94478,676.16171 492.11405,676.8158 490.6159,676.8158 C 489.13952,676.8158 488.28919,676.16171 488.28919,674.69589 z" /> + d="M 493.14947,670.83211 L 493.26053,669.47494 H 497.56335 L 497.6951,670.83211 H 496.2884 V 676.67731 H 494.62802 V 670.83211 H 493.14947 z" /> + d="M 497.927,669.47494 H 499.57867 V 676.67731 H 497.927 V 669.47494 z" /> + d="M 499.85086,673.05109 C 499.85086,671.24864 500.54006,669.27787 502.68603,669.28745 C 504.8222,669.27745 505.51139,671.24864 505.50159,673.05109 C 505.50159,674.87379 504.85377,676.82538 502.68603,676.8158 C 500.50957,676.8258 499.87264,674.87379 499.85086,673.05109 z M 501.55262,673.07129 C 501.55262,674.062 501.75513,675.48842 502.68603,675.52783 C 503.60822,675.48733 503.80964,674.062 503.80964,673.07129 C 503.80964,672.09017 503.60713,670.82248 502.68603,670.76283 C 501.75404,670.82253 501.55262,672.09017 501.55262,673.07129 z" /> + d="M 505.7531,676.67731 V 669.47494 H 507.1206 L 508.66992,673.01168 V 669.47494 H 510.23013 V 676.67731 H 508.93449 L 507.33509,673.15016 V 676.67731 H 505.7531 z" /> + d="M 132.598,20.466 C 132.598,21.246378 131.96538,21.879 131.185,21.879 C 130.40462,21.879 129.772,21.246378 129.772,20.466 C 129.772,19.685621 130.40462,19.053 131.185,19.053 C 131.96538,19.053 132.598,19.685621 132.598,20.466 z" /> + d="M 153.14499,29.417 C 153.14499,30.197378 152.51237,30.83 151.73199,30.83 C 150.95162,30.83 150.31899,30.197378 150.31899,29.417 C 150.31899,28.636621 150.95162,28.004 151.73199,28.004 C 152.51237,28.004 153.14499,28.636621 153.14499,29.417 z" /> + d="M 1286.1956,653.36166 C 1286.1956,653.78235 1286.0277,654.13224 1285.692,654.41134 C 1285.3764,654.68236 1285.0043,654.81787 1284.5755,654.81786 C 1284.1427,654.81786 1283.7746,654.68438 1283.4712,654.41741 L 1281.4568,660.01166 C 1281.2667,660.54965 1280.937,660.81864 1280.4678,660.81864 C 1279.8368,660.81864 1279.4626,660.5456 1279.3453,659.99953 L 1278.3381,655.22439 L 1276.9729,659.26536 C 1276.8314,659.68604 1276.5603,660.02178 1276.1599,660.27256 C 1275.7837,660.51122 1275.3671,660.63055 1274.91,660.63055 L 1272.0279,660.63055 C 1272.2059,660.1856 1272.3576,659.87211 1272.483,659.69008 C 1272.7216,659.33817 1273.0007,659.16221 1273.3203,659.16221 C 1273.5144,659.16221 1273.8077,659.20471 1274.2001,659.28963 C 1274.5965,659.37053 1274.8958,659.41098 1275.0981,659.41098 C 1275.5228,659.41098 1275.8241,659.15007 1276.0021,658.62827 L 1277.8709,653.20997 C 1278.0287,652.74076 1278.1642,652.43941 1278.2775,652.30591 C 1278.4676,652.06322 1278.7669,651.94187 1279.1754,651.94186 C 1279.7862,651.94186 1280.1786,652.37266 1280.3525,653.23424 L 1281.1838,657.38443 L 1282.4398,653.85919 C 1282.9049,652.55671 1283.6128,651.90546 1284.5634,651.90545 C 1284.9922,651.90545 1285.3663,652.03895 1285.6859,652.30591 C 1286.0257,652.58907 1286.1956,652.94099 1286.1956,653.36166" /> + d="M 1291.7352,659.65974 C 1291.541,660.30695 1291.0455,660.63055 1290.2487,660.63055 L 1287.9491,660.63055 C 1287.2938,660.63055 1286.9661,660.42021 1286.9661,659.99953 C 1286.5252,660.50111 1285.9832,660.7519 1285.34,660.7519 C 1284.8668,660.7519 1284.4825,660.60628 1284.1872,660.31504 C 1283.8919,660.0238 1283.7443,659.64357 1283.7443,659.17434 C 1283.7443,658.32894 1284.0679,657.66151 1284.7151,657.17206 C 1285.3016,656.72712 1286.0277,656.50464 1286.8933,656.50464 L 1290.3579,656.50464 L 1289.2172,659.65974 L 1291.7352,659.65974 M 1287.8217,657.47544 L 1286.4807,657.47544 L 1286.056,658.88917 C 1286.032,658.97817 1286.02,659.05906 1286.02,659.13187 C 1286.02,659.48379 1286.3638,659.65974 1287.0515,659.65974 L 1287.8221,657.47544" /> + d="M 1300.0477,659.65974 C 1299.9425,660.01571 1299.7099,660.27863 1299.3499,660.44852 C 1299.0951,660.56987 1298.8221,660.63055 1298.5308,660.63055 L 1296.1099,660.63055 C 1295.5557,660.63055 1295.2786,660.44852 1295.2786,660.08447 C 1295.2786,659.96312 1295.3066,659.82155 1295.3636,659.65974 L 1295.8247,658.35523 L 1293.7375,660.12088 C 1293.248,660.46066 1292.8456,660.63055 1292.5301,660.63055 L 1291.4136,660.63055 L 1292.8638,656.50464 L 1295.0541,656.50464 L 1294.3685,658.44624 L 1296.2191,656.92936 C 1296.7207,656.52082 1297.2647,656.32464 1297.8513,656.34081 C 1298.2477,656.35701 1298.4459,656.56734 1298.4459,656.97183 C 1298.4459,657.1215 1298.4139,657.28937 1298.3489,657.47544 L 1297.5662,659.65974 L 1300.0478,659.65974" /> + d="M 1310.314,656.50464 C 1310.1521,657.15184 1309.6667,657.47544 1308.8578,657.47544 L 1305.0595,657.47544 C 1305.193,657.56444 1305.3022,657.72825 1305.3871,657.96691 C 1305.4721,658.20152 1305.5065,658.4058 1305.4903,658.57973 C 1305.4333,659.25525 1305.1363,659.78514 1304.5984,660.16942 C 1304.0846,660.53751 1303.4172,660.72358 1302.5961,660.72763 C 1301.6414,660.73563 1300.9073,660.54762 1300.3936,660.16335 C 1299.9365,659.82357 1299.7079,659.3766 1299.7079,658.82243 C 1299.7079,658.71322 1299.7179,658.604 1299.7379,658.49478 C 1299.843,657.88399 1300.1464,657.40465 1300.648,657.05678 C 1301.1819,656.68869 1301.8939,656.50464 1302.7838,656.50464 L 1310.3136,656.50464 M 1303.7,657.47544 L 1302.3105,657.47544 L 1301.7644,659.02873 C 1301.7364,659.10963 1301.7214,659.18648 1301.7214,659.25929 C 1301.7214,659.60716 1302.045,659.7811 1302.6923,659.7811 C 1302.7693,659.7811 1302.8358,659.7791 1302.8925,659.7751 L 1303.6995,657.47551" /> @@ -23806,19 +23843,19 @@ style="font-size:12px;font-style:normal;font-variant:normal;font-weight:bold;font-stretch:normal;line-height:125%;letter-spacing:0px;word-spacing:0px;fill:#000000;fill-opacity:1;stroke:none;font-family:Arial;-inkscape-font-specification:Arial Bold" id="text15590"> @@ -24171,7 +24208,7 @@ style="fill:none;stroke:#000000;stroke-width:0.99212599px;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none" /> + d="M 386.44699,686.89099 C 386.44699,688.40977 385.21577,689.64099 383.69699,689.64099 C 382.17821,689.64099 380.94699,688.40977 380.94699,686.89099 C 380.94699,685.37221 382.17821,684.14099 383.69699,684.14099 C 385.21577,684.14099 386.44699,685.37221 386.44699,686.89099 z" /> + d="M 411.435,717.672 C 411.435,719.19078 410.20378,720.422 408.685,720.422 C 407.16621,720.422 405.935,719.19078 405.935,717.672 C 405.935,716.15321 407.16621,714.922 408.685,714.922 C 410.20378,714.922 411.435,716.15321 411.435,717.672 z" /> + d="M 216.804,613.62 C 216.804,615.13878 215.57278,616.37 214.054,616.37 C 212.53522,616.37 211.304,615.13878 211.304,613.62 C 211.304,612.10121 212.53522,610.87 214.054,610.87 C 215.57278,610.87 216.804,612.10121 216.804,613.62 z" /> + d="M 216.804,613.62 C 216.804,615.13878 215.57278,616.37 214.054,616.37 C 212.53522,616.37 211.304,615.13878 211.304,613.62 C 211.304,612.10121 212.53522,610.87 214.054,610.87 C 215.57278,610.87 216.804,612.10121 216.804,613.62 z" /> + d="M 586.448,613.99402 C 586.448,615.5128 585.21678,616.74402 583.698,616.74402 C 582.17921,616.74402 580.948,615.5128 580.948,613.99402 C 580.948,612.47524 582.17921,611.24402 583.698,611.24402 C 585.21678,611.24402 586.448,612.47524 586.448,613.99402 z" /> + d="M 386.44699,686.89099 C 386.44699,688.40977 385.21577,689.64099 383.69699,689.64099 C 382.17821,689.64099 380.94699,688.40977 380.94699,686.89099 C 380.94699,685.37221 382.17821,684.14099 383.69699,684.14099 C 385.21577,684.14099 386.44699,685.37221 386.44699,686.89099 z" /> + d="M 411.435,717.672 C 411.435,719.19078 410.20378,720.422 408.685,720.422 C 407.16621,720.422 405.935,719.19078 405.935,717.672 C 405.935,716.15321 407.16621,714.922 408.685,714.922 C 410.20378,714.922 411.435,716.15321 411.435,717.672 z" /> Date: Sat, 6 Sep 2014 10:35:43 +1000 Subject: [PATCH 144/203] Fix spelling typeo, make sure npote is visable --- .../src/plugins/setupwizard/pages/airspeedpage.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index 27a9d4a07..cdba16a24 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -60,10 +60,9 @@ void AirSpeedPage::setupSelection(Selection *selection) selection->setTitle(tr("OpenPilot Airspeed Sensor Selection")); selection->setText(tr("This part of the wizard will help you select and configure a way to obtain " "airspeed data. OpenPilot support three methods to achieve this, one is a " - "software estimation technique and the other two utilize hardware sensors.\n" + "software estimation technique and the other two utilize hardware sensors.\n\n" "Note: if previously selected input combinations use the Flexi-port for input, " - "only estimated airspeed will be avilible.\n\n" - "Please select how you wish to obtain airspeed data below:")); + "only estimated airspeed will be available.\n\n")); selection->addItem(tr("Estimated"), tr("This option uses an intelligent estimation algorithm which utilizes the OpenPilot INS/GPS " "to estimate wind speed and subtract it from ground speed obtained from the GPS.\n\n" From e549c71da671783cd23c93d0ff5c84165967aac8 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Wed, 3 Sep 2014 21:14:54 +0200 Subject: [PATCH 145/203] OP-1379 - add unit testing --- Makefile | 2 +- flight/tests/lednotification/FreeRTOS.h | 1 + flight/tests/lednotification/Makefile | 41 ++++++++++ flight/tests/lednotification/openpilot.h | 11 +++ flight/tests/lednotification/pios.h | 13 ++++ flight/tests/lednotification/pios_config.h | 6 ++ flight/tests/lednotification/pios_mem.h | 34 ++++++++ flight/tests/lednotification/unittest.cpp | 90 ++++++++++++++++++++++ make/unittest.mk | 4 + 9 files changed, 201 insertions(+), 1 deletion(-) create mode 100644 flight/tests/lednotification/FreeRTOS.h create mode 100644 flight/tests/lednotification/Makefile create mode 100644 flight/tests/lednotification/openpilot.h create mode 100644 flight/tests/lednotification/pios.h create mode 100644 flight/tests/lednotification/pios_config.h create mode 100644 flight/tests/lednotification/pios_mem.h create mode 100644 flight/tests/lednotification/unittest.cpp diff --git a/Makefile b/Makefile index 48cb90043..219ab95ae 100644 --- a/Makefile +++ b/Makefile @@ -638,7 +638,7 @@ uavo-collections_clean: # ############################## -ALL_UNITTESTS := logfs +ALL_UNITTESTS := logfs lednotification # Build the directory for the unit tests UT_OUT_DIR := $(BUILD_DIR)/unit_tests diff --git a/flight/tests/lednotification/FreeRTOS.h b/flight/tests/lednotification/FreeRTOS.h new file mode 100644 index 000000000..c8b49f26d --- /dev/null +++ b/flight/tests/lednotification/FreeRTOS.h @@ -0,0 +1 @@ +#include diff --git a/flight/tests/lednotification/Makefile b/flight/tests/lednotification/Makefile new file mode 100644 index 000000000..d013f5b83 --- /dev/null +++ b/flight/tests/lednotification/Makefile @@ -0,0 +1,41 @@ +############################################################################### +# @file Makefile +# @author PhoenixPilot, http://github.com/PhoenixPilot, Copyright (C) 2012 +# Copyright (c) 2013, The OpenPilot Team, http://www.openpilot.org +# @addtogroup +# @{ +# @addtogroup +# @{ +# @brief Makefile for unit test +############################################################################### +# +# 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 OPENPILOT_IS_COOL + $(error Top level Makefile must be used to build this target) +endif + +include $(ROOT_DIR)/make/firmware-defs.mk + +EXTRAINCDIRS += $(TOPDIR) +EXTRAINCDIRS += $(PIOS)/inc +EXTRAINCDIRS += $(FLIGHTLIB)/inc +EXTRAINCDIRS += $(FLIGHTLIB) + +SRC += $(FLIGHTLIB)/optypes.c +SRC += $(PIOS)/common/pios_notify.c + +include $(ROOT_DIR)/make/unittest.mk diff --git a/flight/tests/lednotification/openpilot.h b/flight/tests/lednotification/openpilot.h new file mode 100644 index 000000000..4c2259d19 --- /dev/null +++ b/flight/tests/lednotification/openpilot.h @@ -0,0 +1,11 @@ +#ifndef OPENPILOT_H +#define OPENPILOT_H + +#include + +#define PIOS_Assert(x) \ + if (!(x)) { while (1) {; } \ + } +#define PIOS_DEBUG_Assert(x) PIOS_Assert(x) + +#endif /* OPENPILOT_H */ diff --git a/flight/tests/lednotification/pios.h b/flight/tests/lednotification/pios.h new file mode 100644 index 000000000..12cd5e76a --- /dev/null +++ b/flight/tests/lednotification/pios.h @@ -0,0 +1,13 @@ +#ifndef PIOS_H +#define PIOS_H + +/* PIOS Feature Selection */ +#include "pios_config.h" + +#ifdef PIOS_INCLUDE_FREERTOS +/* FreeRTOS Includes */ +#include "FreeRTOS.h" +#endif +#include "pios_mem.h" + +#endif /* PIOS_H */ diff --git a/flight/tests/lednotification/pios_config.h b/flight/tests/lednotification/pios_config.h new file mode 100644 index 000000000..2a645e951 --- /dev/null +++ b/flight/tests/lednotification/pios_config.h @@ -0,0 +1,6 @@ +#ifndef PIOS_CONFIG_H +#define PIOS_CONFIG_H + +#define PIOS_INCLUDE_FREERTOS + +#endif /* PIOS_CONFIG_H */ diff --git a/flight/tests/lednotification/pios_mem.h b/flight/tests/lednotification/pios_mem.h new file mode 100644 index 000000000..279ce5aef --- /dev/null +++ b/flight/tests/lednotification/pios_mem.h @@ -0,0 +1,34 @@ +/** + ****************************************************************************** + * + * @file pios_mem.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2014. + * @addtogroup PiOS + * @{ + * @addtogroup PiOS + * @{ + * @brief PiOS memory allocation API + *****************************************************************************/ +/* + * 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 PIOS_MEM_H +#define PIOS_MEM_H + +#define pios_fastheapmalloc(size) (malloc(size)) +#define pios_malloc(size) (malloc(size)) +#define pios_free(p) (free(p)) + +#endif /* PIOS_MEM_H */ diff --git a/flight/tests/lednotification/unittest.cpp b/flight/tests/lednotification/unittest.cpp new file mode 100644 index 000000000..80ef7d8a4 --- /dev/null +++ b/flight/tests/lednotification/unittest.cpp @@ -0,0 +1,90 @@ +#include "gtest/gtest.h" + +#include /* printf */ +#include /* abort */ +#include /* memset */ + +extern "C" { +#define xTaskGetTickCount() 1 +#define portTICK_RATE_MS 1 + +#include "lednotification.c" + +void PIOS_WS2811_setColorRGB(__attribute__((unused)) Color_t c, __attribute__((unused)) uint8_t led, __attribute__((unused)) bool update){ + +} +void PIOS_WS2811_Update(){ + +} +} + +class LedNotificationTest : public testing::Test {}; + +TEST_F(LedNotificationTest, TestQueueOrder1) { + NotifierLedStatus_t status; + + for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { + status.queued_priorities[i] = NOTIFY_PRIORITY_BACKGROUND; + } + + + ExtLedNotification_t notification0; + notification0.priority = NOTIFY_PRIORITY_LOW; + push_queued_sequence(¬ification0, &status); + ExtLedNotification_t notification1; + notification1.priority = NOTIFY_PRIORITY_CRITICAL; + push_queued_sequence(¬ification1, &status); + ExtLedNotification_t notification2; + notification2.priority = NOTIFY_PRIORITY_LOW; + push_queued_sequence(¬ification2, &status); + ExtLedNotification_t notification3; + notification3.priority = NOTIFY_PRIORITY_CRITICAL; + push_queued_sequence(¬ification3, &status); + + EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[0]); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[1]); + EXPECT_EQ(NOTIFY_PRIORITY_CRITICAL, status.queued_priorities[2]); + EXPECT_EQ(NOTIFY_PRIORITY_CRITICAL, status.queued_priorities[3]); + EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, status.queued_priorities[4]); + +} + +TEST_F(LedNotificationTest, TestQueueOrder2) { + NotifierLedStatus_t status; + +// Fails because insert_point and first_point will both be -1. This will also cause an array-out-of bounds at: +// 146 status->queued_priorities[insert_point] = new_notification->priority; +// 147 status->queued_sequences[insert_point] = new_notification->sequence; +// 148 updated_sequence = insert_point; + + for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { + status.queued_priorities[i] = NOTIFY_PRIORITY_LOW; + } + + ExtLedNotification_t notification; + notification.priority = NOTIFY_PRIORITY_REGULAR; + push_queued_sequence(¬ification, &status); + + EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, status.queued_priorities[4]); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[3]); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[2]); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[1]); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[0]); +} + +TEST_F(LedNotificationTest, TestQueueOrder3) { + NotifierLedStatus_t status; + + // Fails because queued_priorities[0] _LOW and not _REGULAR. I _think_ this is a bug. + for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { + status.queued_priorities[i] = NOTIFY_PRIORITY_REGULAR; + } + + ExtLedNotification_t notification; + notification.priority = NOTIFY_PRIORITY_LOW; + push_queued_sequence(¬ification, &status); + + for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { + EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, status.queued_priorities[i]); + } +} diff --git a/make/unittest.mk b/make/unittest.mk index 5963f5567..2190a6ab4 100644 --- a/make/unittest.mk +++ b/make/unittest.mk @@ -52,6 +52,10 @@ CXXFLAGS += -g -Wall -Wextra # Flags passed to the C compiler CONLYFLAGS += -std=gnu99 +# UNIT_TEST allows to for example to have optional test fixture code enabled or private code exposed in application modules. +CFLAGS += -DUNIT_TEST +CPPFLAGS += -DUNIT_TEST + # Common compiler flags CFLAGS += -O0 -g CFLAGS += -Wall -Werror From 233dec6d8d753cba97ef4db9a14baacb1a5bce56 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Mon, 18 Aug 2014 16:35:02 +0200 Subject: [PATCH 146/203] OP-1379 - Various fixes and additions MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Support blocks of led for notification (that is a certain number of leds between a min and a max index); - Fix an issue with bogus colours on fast updates at LED N°0. - Add NOTIFY_SEQUENCE_NULL to skip handling a specific alarm status; - Adjust sequences and add Config and Receiver Alarms; - fix issue with Alarm trigger/repetition; - Enables Notify module only if a WS281x output is enabled. - Add some documentation for sequence/alarm definitions (sequences.h) - Make sequences more coherent. All GPS related info are now shown in green. - Revert to original blinking rate for onboard led - add Notify on DiscoveryF4Bare target --- flight/libraries/inc/notification.h | 2 +- flight/libraries/lednotification.c | 31 +- flight/modules/Notify/inc/sequences.h | 435 +++++------------- flight/modules/Notify/notify.c | 42 +- flight/pios/inc/pios_ws2811_cfg.h | 1 - flight/pios/stm32f4xx/pios_ws2811.c | 8 + .../boards/discoveryf4bare/firmware/Makefile | 1 + flight/tests/lednotification/unittest.cpp | 77 ++-- 8 files changed, 219 insertions(+), 378 deletions(-) diff --git a/flight/libraries/inc/notification.h b/flight/libraries/inc/notification.h index 2053a9609..2091d9189 100644 --- a/flight/libraries/inc/notification.h +++ b/flight/libraries/inc/notification.h @@ -27,7 +27,7 @@ #define NOTIFICATION_H // period of each blink phase -#define LED_BLINK_PERIOD_MS 200 +#define LED_BLINK_PERIOD_MS 50 // update the status snapshot used by notifcations void NotificationUpdateStatus(); diff --git a/flight/libraries/lednotification.c b/flight/libraries/lednotification.c index b2ca13597..4b5950d17 100644 --- a/flight/libraries/lednotification.c +++ b/flight/libraries/lednotification.c @@ -27,8 +27,8 @@ #include #include #include -#include -#include +#include +#include #include #include @@ -57,7 +57,8 @@ typedef struct { uint8_t next_sequence_step; // (step number to be executed) << 1 || (0x00 = on phase, 0x01 = off phase) uint8_t next_step_rep; // next repetition number for next step (valid if step.repeats >1) uint8_t next_sequence_rep; // next sequence repetition counter (valid if sequence.repeats > 1) - uint8_t led_set; // target led set + uint8_t led_set_start; // first target led for this set + uint8_t led_set_end; // last target led for this set } NotifierLedStatus_t; static bool led_status_initialized = false; @@ -69,7 +70,8 @@ static void InitExtLed() memset(led_status, 0, sizeof(NotifierLedStatus_t) * MAX_HANDLED_LED); const uint32_t now = GET_CURRENT_MILLIS; for (uint8_t l = 0; l < MAX_HANDLED_LED; l++) { - led_status[l].led_set = 0; + led_status[l].led_set_start = 0; + led_status[l].led_set_end = PIOS_WS2811_NUMLEDS - 1; led_status[l].next_run_time = now + 500; // start within half a second for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { led_status[l].queued_priorities[i] = NOTIFY_PRIORITY_BACKGROUND; @@ -105,9 +107,9 @@ static void push_queued_sequence(ExtLedNotification_t *new_notification, Notifie } else { // a notification with priority higher than background. // try to enqueue it - int8_t insert_point = -1; + int8_t insert_point = MAX_BACKGROUND_NOTIFICATIONS - 1; int8_t first_free = -1; - for (int8_t i = MAX_BACKGROUND_NOTIFICATIONS; i > -1; i--) { + for (int8_t i = MAX_BACKGROUND_NOTIFICATIONS - 1; i >= 0; i--) { const int8_t priority_i = status->queued_priorities[i]; if (priority_i == NOTIFY_PRIORITY_BACKGROUND) { first_free = i; @@ -115,10 +117,14 @@ static void push_queued_sequence(ExtLedNotification_t *new_notification, Notifie continue; } if (priority_i > new_notification->priority) { - insert_point = i; + insert_point = ((i > 0) || (first_free > -1)) ? i : -1; // check whether priority is no bigger than lowest queued priority } } + // no space left on queue for this new notification, ignore. + if (insert_point < 0) { + return; + } if (insert_point != first_free) { // there is a free slot, move everything up one place if (first_free != -1) { @@ -230,7 +236,7 @@ static void advance_sequence(NotifierLedStatus_t *status) */ static void run_led(NotifierLedStatus_t *status) { - uint32_t currentTime = GET_CURRENT_MILLIS; + const uint32_t currentTime = GET_CURRENT_MILLIS; if (!status->running || currentTime < status->next_run_time) { return; @@ -240,11 +246,12 @@ static void run_led(NotifierLedStatus_t *status) LedSequence_t *activeSequence = status->active_sequence_num == BACKGROUND_SEQUENCE ? &status->background_sequence : &status->queued_sequences[status->active_sequence_num]; - if (status->step_phase_on) { - PIOS_WS2811_setColorRGB(activeSequence->steps[step].color, status->led_set, true); - } else { - PIOS_WS2811_setColorRGB(Color_Off, status->led_set, true); + const Color_t color = status->step_phase_on ? activeSequence->steps[step].color : Color_Off; + + for (uint8_t i = status->led_set_start; i <= status->led_set_end; i++) { + PIOS_WS2811_setColorRGB(color, i, false); } + PIOS_WS2811_Update(); advance_sequence(status); } diff --git a/flight/modules/Notify/inc/sequences.h b/flight/modules/Notify/inc/sequences.h index ebb9bafb6..c28f90c15 100644 --- a/flight/modules/Notify/inc/sequences.h +++ b/flight/modules/Notify/inc/sequences.h @@ -31,6 +31,7 @@ #include #include +// This represent the list of basic light sequences, defined later typedef enum { NOTIFY_SEQUENCE_ARMED_FM_MANUAL = 0, NOTIFY_SEQUENCE_ARMED_FM_STABILIZED1 = 1, @@ -48,330 +49,120 @@ typedef enum { NOTIFY_SEQUENCE_ALM_ERROR_GPS = 13, NOTIFY_SEQUENCE_ALM_WARN_BATTERY = 14, NOTIFY_SEQUENCE_ALM_ERROR_BATTERY = 15, - NOTIFY_SEQUENCE_ALM_MAG = 16, + NOTIFY_SEQUENCE_ALM_MAG = 16, NOTIFY_SEQUENCE_ALM_CONFIG = 17, - NOTIFY_SEQUENCE_DISARMED = 18, + NOTIFY_SEQUENCE_ALM_RECEIVER = 18, + NOTIFY_SEQUENCE_DISARMED = 19, + NOTIFY_SEQUENCE_NULL = 255, // skips any signalling for this condition } NotifySequences; +// This structure determine sequences attached to an alarm typedef struct { - uint32_t timeBetweenNotifications; - uint8_t alarmIndex; - uint8_t warnNotification; - uint8_t errorNotification; + uint32_t timeBetweenNotifications; // time in milliseconds to wait between each notification iteration + uint8_t alarmIndex; // Index of the alarm, use one of the SYSTEMALARMS_ALARM_XXXXX defines + uint8_t warnNotification; // index of the sequence to be used when alarm is in warning status(pick one from NotifySequences enum) + uint8_t errorNotification; // index of the sequence to be used when alarm is in error status(pick one from NotifySequences enum) } AlarmDefinition_t; -// consts + +// This is the list of defined light sequences +/* how each sequence is defined + * [NOTIFY_SEQUENCE_DISARMED] = { // Sequence ID + .repeats = -1, // Number of repetitions or -1 for infinite + .steps = { // List of steps (until NOTIFY_SEQUENCE_MAX_STEPS steps, default to 5) + { + .time_off = 500, // Off time for the step + .time_on = 500, // On time for the step + .color = COLOR_TEAL, // color + .repeats = 1, // repetitions for this step + }, + }, + }, + * + * There are two kind of sequences: + * - "Background" sequences, executed if no higher priority sequence is played; + * - "Alarm" sequences, that are "modal", they temporarily suspends background sequences and plays. + * Cannot have "-1" repetitions + * At the end background sequence are resumed; + * + */ const LedSequence_t notifications[] = { - [NOTIFY_SEQUENCE_DISARMED] = { - .repeats = -1, - .steps = { - { - .time_off = 1000, - .time_on = 1000, - .color = COLOR_BLUE, - .repeats = 1, - }, - { - .time_off = 1000, - .time_on = 1000, - .color = COLOR_LIME, - .repeats = 1, - }, - { - .time_off = 1000, - .time_on = 1000, - .color = COLOR_RED, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ARMED_FM_MANUAL] = { - .repeats = -1, - .steps = { - { - .time_off = 900, - .time_on = 100, - .color = COLOR_YELLOW, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED1] = { - .repeats = -1, - .steps = { - { - .time_off = 900, - .time_on = 100, - .color = COLOR_BLUE, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED2] = { - .repeats = -1, - .steps = { - { - .time_off = 100, - .time_on = 100, - .color = COLOR_BLUE, - .repeats = 1, - }, - { - .time_off = 700, - .time_on = 100, - .color = COLOR_BLUE, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED3] = { - .repeats = -1, - .steps = { - { - .time_off = 100, - .time_on = 100, - .color = COLOR_BLUE, - .repeats = 2, - }, - { - .time_off = 500, - .time_on = 100, - .color = COLOR_BLUE, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED4] = { - .repeats = -1, - .steps = { - { - .time_off = 900, - .time_on = 100, - .color = COLOR_PURPLE, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED5] = { - .repeats = -1, - .steps = { - { - .time_off = 100, - .time_on = 100, - .color = COLOR_PURPLE, - .repeats = 1, - }, - { - .time_off = 700, - .time_on = 100, - .color = COLOR_BLUE, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED6] = { - .repeats = -1, - .steps = { - { - .time_off = 100, - .time_on = 100, - .color = COLOR_PURPLE, - .repeats = 1, - }, - { - .time_off = 100, - .time_on = 100, - .color = COLOR_PURPLE, - .repeats = 1, - }, - { - .time_off = 500, - .time_on = 100, - .color = COLOR_BLUE, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ARMED_FM_AUTOTUNE] = { - .repeats = -1, - .steps = { - { - .time_off = 800, - .time_on = 200, - .color = COLOR_BLUE, - .repeats = 1, - }, - }, - }, + [NOTIFY_SEQUENCE_DISARMED] = { .repeats = -1, .steps = { + { .time_off = 500, .time_on = 500, .color = COLOR_TEAL, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ARMED_FM_MANUAL] = { .repeats = -1, .steps = { + { .time_off = 900, .time_on = 100, .color = COLOR_YELLOW, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED1] = { .repeats = -1, .steps = { + { .time_off = 900, .time_on = 100, .color = COLOR_BLUE, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED2] = { .repeats = -1, .steps = { + { .time_off = 100, .time_on = 100, .color = COLOR_BLUE, .repeats = 1, }, + { .time_off = 700, .time_on = 100, .color = COLOR_BLUE, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED3] = { .repeats = -1, .steps = { + { .time_off = 100, .time_on = 100, .color = COLOR_BLUE, .repeats = 2, }, + { .time_off = 500, .time_on = 100, .color = COLOR_BLUE, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED4] = { .repeats = -1, .steps = { + { .time_off = 900, .time_on = 100, .color = COLOR_PURPLE, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED5] = { .repeats = -1, .steps = { + { .time_off = 100, .time_on = 100, .color = COLOR_PURPLE, .repeats = 1, }, + { .time_off = 700, .time_on = 100, .color = COLOR_BLUE, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ARMED_FM_STABILIZED6] = { .repeats = -1, .steps = { + { .time_off = 100, .time_on = 100, .color = COLOR_PURPLE, .repeats = 1, }, + { .time_off = 100, .time_on = 100, .color = COLOR_PURPLE, .repeats = 1, }, + { .time_off = 500, .time_on = 100, .color = COLOR_BLUE, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ARMED_FM_AUTOTUNE] = { .repeats = -1, .steps = { + { .time_off = 800, .time_on = 200, .color = COLOR_BLUE, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ARMED_FM_GPS] = { .repeats = -1, .steps = { + { .time_off = 800, .time_on = 200, .color = COLOR_GREEN, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ARMED_FM_RTH] = { .repeats = -1, .steps = { + { .time_off = 100, .time_on = 100, .color = COLOR_GREEN, .repeats = 1, }, + { .time_off = 100, .time_on = 100, .color = COLOR_YELLOW, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ARMED_FM_LAND] = { .repeats = -1, .steps = { + { .time_off = 100, .time_on = 100, .color = COLOR_GREEN, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ARMED_FM_AUTO] = { .repeats = -1, .steps = { + { .time_off = 100, .time_on = 200, .color = COLOR_GREEN, .repeats = 2, }, + { .time_off = 500, .time_on = 200, .color = COLOR_GREEN, .repeats = 1, }, + }, }, - [NOTIFY_SEQUENCE_ARMED_FM_GPS] = { - .repeats = -1, - .steps = { - { - .time_off = 800, - .time_on = 200, - .color = COLOR_GREEN, - .repeats = 1, - }, - }, - }, - - [NOTIFY_SEQUENCE_ARMED_FM_RTH] = { - .repeats = -1, - .steps = { - { - .time_off = 100, - .time_on = 200, - .color = COLOR_GREEN, - .repeats = 1, - }, - { - .time_off = 500, - .time_on = 200, - .color = COLOR_GREEN, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ARMED_FM_LAND] = { - .repeats = -1, - .steps = { - { - .time_off = 100, - .time_on = 200, - .color = COLOR_GREEN, - .repeats = 1, - }, - { - .time_off = 100, - .time_on = 200, - .color = COLOR_BLUE, - .repeats = 1, - }, - { - .time_off = 100, - .time_on = 200, - .color = COLOR_GREEN, - .repeats = 1, - }, - { - .time_off = 100, - .time_on = 200, - .color = COLOR_BLUE, - .repeats = 1, - }, - { - .time_off = 100, - .time_on = 200, - .color = COLOR_GREEN, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ARMED_FM_AUTO] = { - .repeats = -1, - .steps = { - { - .time_off = 100, - .time_on = 200, - .color = COLOR_GREEN, - .repeats = 2, - }, - { - .time_off = 500, - .time_on = 200, - .color = COLOR_GREEN, - .repeats = 1, - }, - }, - }, - - [NOTIFY_SEQUENCE_ALM_WARN_GPS] = { - .repeats = 2, - .steps = { - { - .time_off = 300, - .time_on = 300, - .color = COLOR_ORANGE, - .repeats = 2, - }, - { - .time_off = 300, - .time_on = 300, - .color = COLOR_YELLOW, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ALM_ERROR_GPS] = { - .repeats = 2, - .steps = { - { - .time_off = 300, - .time_on = 300, - .color = COLOR_RED, - .repeats = 2, - }, - { - .time_off = 300, - .time_on = 300, - .color = COLOR_YELLOW, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ALM_WARN_BATTERY] = { - .repeats = 1, - .steps = { - { - .time_off = 100, - .time_on = 100, - .color = COLOR_ORANGE, - .repeats = 10, - }, - }, - }, - [NOTIFY_SEQUENCE_ALM_ERROR_BATTERY] = { - .repeats = 1, - .steps = { - { - .time_off = 100, - .time_on = 100, - .color = COLOR_RED, - .repeats = 10, - }, - }, - }, - [NOTIFY_SEQUENCE_ALM_MAG] = { - .repeats = 1, - .steps = { - { - .time_off = 300, - .time_on = 300, - .color = COLOR_RED, - .repeats = 2, - }, - { - .time_off = 300, - .time_on = 300, - .color = COLOR_GREEN, - .repeats = 1, - }, - }, - }, - [NOTIFY_SEQUENCE_ALM_CONFIG] = { - .repeats = -1, - .steps = { - { - .time_off = 500, - .time_on = 100, - .color = COLOR_RED, - .repeats = 1, - }, - }, - }, + [NOTIFY_SEQUENCE_ALM_WARN_GPS] = { .repeats = 2, .steps = { + { .time_off = 300, .time_on = 300, .color = COLOR_ORANGE, .repeats = 2, }, + { .time_off = 300, .time_on = 300, .color = COLOR_GREEN, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ALM_ERROR_GPS] = { .repeats = 2, .steps = { + { .time_off = 300, .time_on = 300, .color = COLOR_RED, .repeats = 2, }, + { .time_off = 300, .time_on = 300, .color = COLOR_GREEN, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ALM_WARN_BATTERY] = { .repeats = 1, .steps = { + { .time_off = 100, .time_on = 100, .color = COLOR_ORANGE, .repeats = 10, }, + }, }, + [NOTIFY_SEQUENCE_ALM_ERROR_BATTERY] = { .repeats = 1, .steps = { + { .time_off = 100, .time_on = 100, .color = COLOR_RED, .repeats = 10, }, + }, }, + [NOTIFY_SEQUENCE_ALM_MAG] = { .repeats = 1, .steps = { + { .time_off = 300, .time_on = 300, .color = COLOR_RED, .repeats = 2, }, + { .time_off = 300, .time_on = 300, .color = COLOR_PURPLE, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ALM_CONFIG] = { .repeats = 1, .steps = { + { .time_off = 50, .time_on = 50, .color = COLOR_RED, .repeats = 9, }, + { .time_off = 500, .time_on = 50, .color = COLOR_RED, .repeats = 1, }, + }, }, + [NOTIFY_SEQUENCE_ALM_RECEIVER] = { .repeats = 1, .steps = { + { .time_off = 50, .time_on = 50, .color = COLOR_ORANGE, .repeats = 9, }, + { .time_off = 500, .time_on = 50, .color = COLOR_ORANGE, .repeats = 1, }, + }, }, }; +// List of background sequences attached to each flight mode const LedSequence_t *flightModeMap[] = { [FLIGHTSTATUS_FLIGHTMODE_MANUAL] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_MANUAL], [FLIGHTSTATUS_FLIGHTMODE_STABILIZED1] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_STABILIZED1], @@ -392,6 +183,7 @@ const LedSequence_t *flightModeMap[] = { [FLIGHTSTATUS_FLIGHTMODE_AUTOCRUISE] = ¬ifications[NOTIFY_SEQUENCE_ARMED_FM_GPS], }; +// List of alarms to show with attached sequences for each status const AlarmDefinition_t alarmsMap[] = { { .timeBetweenNotifications = 10000, @@ -402,7 +194,7 @@ const AlarmDefinition_t alarmsMap[] = { { .timeBetweenNotifications = 15000, .alarmIndex = SYSTEMALARMS_ALARM_MAGNETOMETER, - .warnNotification = NOTIFY_SEQUENCE_ALM_MAG, + .warnNotification = NOTIFY_SEQUENCE_NULL, .errorNotification = NOTIFY_SEQUENCE_ALM_MAG, }, { @@ -411,7 +203,20 @@ const AlarmDefinition_t alarmsMap[] = { .warnNotification = NOTIFY_SEQUENCE_ALM_WARN_BATTERY, .errorNotification = NOTIFY_SEQUENCE_ALM_ERROR_BATTERY, }, + { + .timeBetweenNotifications = 5000, + .alarmIndex = SYSTEMALARMS_ALARM_SYSTEMCONFIGURATION, + .warnNotification = NOTIFY_SEQUENCE_NULL, + .errorNotification = NOTIFY_SEQUENCE_ALM_CONFIG, + }, + { + .timeBetweenNotifications = 5000, + .alarmIndex = SYSTEMALARMS_ALARM_RECEIVER, + .warnNotification = NOTIFY_SEQUENCE_ALM_RECEIVER, + .errorNotification = NOTIFY_SEQUENCE_ALM_RECEIVER, + }, }; + const uint8_t alarmsMapSize = NELEMENTS(alarmsMap); #endif /* SEQUENCES_H_ */ diff --git a/flight/modules/Notify/notify.c b/flight/modules/Notify/notify.c index a944690cb..8ccb3cdc4 100644 --- a/flight/modules/Notify/notify.c +++ b/flight/modules/Notify/notify.c @@ -49,12 +49,13 @@ #include #include #include -#include +#include #include #include #include "inc/notify.h" #include "inc/sequences.h" #include +#include #define SAMPLE_PERIOD_MS 250 // private types @@ -71,17 +72,26 @@ static void checkAlarm(uint8_t alarm, uint8_t *last_alarm, uint32_t *last_alm_ti static AlarmStatus_t *alarmStatus; int32_t NotifyInitialize(void) { - alarmStatus = (AlarmStatus_t *)pios_malloc(sizeof(AlarmStatus_t) * alarmsMapSize); - for (uint8_t i = 0; i < alarmsMapSize; i++) { - alarmStatus[i].lastAlarm = SYSTEMALARMS_ALARM_OK; - alarmStatus[i].lastAlarmTime = 0; - } + uint8_t ws281xOutStatus; - FlightStatusConnectCallback(&updatedCb); - updatedCb(0); - static UAVObjEvent ev; - memset(&ev, 0, sizeof(UAVObjEvent)); - EventPeriodicCallbackCreate(&ev, onTimerCb, SAMPLE_PERIOD_MS / portTICK_RATE_MS); + HwSettingsWS2811LED_OutGet(&ws281xOutStatus); + // Todo: Until further applications exists for WS2811 notify enabled status is tied to ws281x output configuration + bool enabled = ws281xOutStatus != HWSETTINGS_WS2811LED_OUT_DISABLED; + + if (enabled) { + alarmStatus = (AlarmStatus_t *)pios_malloc(sizeof(AlarmStatus_t) * alarmsMapSize); + for (uint8_t i = 0; i < alarmsMapSize; i++) { + alarmStatus[i].lastAlarm = SYSTEMALARMS_ALARM_OK; + alarmStatus[i].lastAlarmTime = 0; + } + + FlightStatusConnectCallback(&updatedCb); + static UAVObjEvent ev; + memset(&ev, 0, sizeof(UAVObjEvent)); + EventPeriodicCallbackCreate(&ev, onTimerCb, SAMPLE_PERIOD_MS / portTICK_RATE_MS); + + updatedCb(0); + } return 0; } MODULE_INITCALL(NotifyInitialize, 0); @@ -128,11 +138,13 @@ void checkAlarm(uint8_t alarm, uint8_t *last_alarm, uint32_t *last_alm_time, uin { if (alarm > SYSTEMALARMS_ALARM_OK) { uint32_t current_time = PIOS_DELAY_GetuS(); - if (*last_alarm < alarm || *last_alm_time + timeBetweenNotifications < current_time) { + if (*last_alarm < alarm || *last_alm_time + timeBetweenNotifications * 1000 < current_time) { uint8_t sequence = (alarm == SYSTEMALARMS_ALARM_WARNING) ? warn_sequence : error_sequence; - PIOS_NOTIFICATION_Default_Ext_Led_Play( - ¬ifications[sequence], - alarm == SYSTEMALARMS_ALARM_WARNING ? NOTIFY_PRIORITY_REGULAR : NOTIFY_PRIORITY_CRITICAL); + if (sequence != NOTIFY_SEQUENCE_NULL) { + PIOS_NOTIFICATION_Default_Ext_Led_Play( + ¬ifications[sequence], + alarm == SYSTEMALARMS_ALARM_WARNING ? NOTIFY_PRIORITY_REGULAR : NOTIFY_PRIORITY_CRITICAL); + } *last_alarm = alarm; *last_alm_time = current_time; } diff --git a/flight/pios/inc/pios_ws2811_cfg.h b/flight/pios/inc/pios_ws2811_cfg.h index 379df77be..d4d7085fb 100644 --- a/flight/pios/inc/pios_ws2811_cfg.h +++ b/flight/pios/inc/pios_ws2811_cfg.h @@ -38,7 +38,6 @@ #include #include -#define sign(x) ((x > 0) - (x < 0)) #define PIOS_WS2811_BUFFER_SIZE (((PIOS_WS2811_NUMLEDS) * 24)) #define PIOS_WS2811_MEMORYDATASIZE DMA_MemoryDataSize_HalfWord #define PIOS_WS2811_PERIPHERALDATASIZE DMA_PeripheralDataSize_HalfWord diff --git a/flight/pios/stm32f4xx/pios_ws2811.c b/flight/pios/stm32f4xx/pios_ws2811.c index 7762cdfb5..b126a08d9 100644 --- a/flight/pios/stm32f4xx/pios_ws2811.c +++ b/flight/pios/stm32f4xx/pios_ws2811.c @@ -310,6 +310,7 @@ void PIOS_WS2811_setColorRGB(Color_t c, uint8_t led, bool update) setColor(c.G, fb + (led * 24)); setColor(c.R, fb + 8 + (led * 24)); setColor(c.B, fb + 16 + (led * 24)); + if (update) { PIOS_WS2811_Update(); } @@ -327,6 +328,10 @@ void PIOS_WS2811_Update() // reset counters for synchronization pios_ws2811_cfg->timer->CNT = PIOS_WS2811_TIM_PERIOD - 1; + + DMA_Cmd(pios_ws2811_cfg->streamCh2, ENABLE); + DMA_Cmd(pios_ws2811_cfg->streamCh1, ENABLE); + DMA_Cmd(pios_ws2811_cfg->streamUpdate, ENABLE); // Start a new cycle TIM_Cmd(pios_ws2811_cfg->timer, ENABLE); } @@ -339,6 +344,9 @@ void PIOS_WS2811_DMA_irq_handler() { pios_ws2811_cfg->timer->CR1 &= (uint16_t) ~TIM_CR1_CEN; DMA_ClearFlag(pios_ws2811_cfg->streamCh1, pios_ws2811_cfg->irq.flags); + DMA_Cmd(pios_ws2811_cfg->streamCh2, DISABLE); + DMA_Cmd(pios_ws2811_cfg->streamCh1, DISABLE); + DMA_Cmd(pios_ws2811_cfg->streamUpdate, DISABLE); } #endif // PIOS_INCLUDE_WS2811 diff --git a/flight/targets/boards/discoveryf4bare/firmware/Makefile b/flight/targets/boards/discoveryf4bare/firmware/Makefile index 29cf57378..d60373ee4 100644 --- a/flight/targets/boards/discoveryf4bare/firmware/Makefile +++ b/flight/targets/boards/discoveryf4bare/firmware/Makefile @@ -35,6 +35,7 @@ USE_DSP_LIB ?= NO #MODULES += Airspeed #MODULES += AltitudeHold #MODULES += Stabilization +MODULES += Notify MODULES += VtolPathFollower MODULES += ManualControl MODULES += Actuator diff --git a/flight/tests/lednotification/unittest.cpp b/flight/tests/lednotification/unittest.cpp index 80ef7d8a4..3d289ffec 100644 --- a/flight/tests/lednotification/unittest.cpp +++ b/flight/tests/lednotification/unittest.cpp @@ -10,43 +10,43 @@ extern "C" { #include "lednotification.c" -void PIOS_WS2811_setColorRGB(__attribute__((unused)) Color_t c, __attribute__((unused)) uint8_t led, __attribute__((unused)) bool update){ - -} -void PIOS_WS2811_Update(){ - -} +void PIOS_WS2811_setColorRGB(__attribute__((unused)) Color_t c, __attribute__((unused)) uint8_t led, __attribute__((unused)) bool update) {} +void PIOS_WS2811_Update() {} } class LedNotificationTest : public testing::Test {}; +void insert(NotifierLedStatus_t *status, pios_notify_priority priority) +{ + ExtLedNotification_t notification; + + notification.priority = priority; + push_queued_sequence(¬ification, status); +} + +void init(NotifierLedStatus_t *status, pios_notify_priority priority) +{ + for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { + status->queued_priorities[i] = priority; + } +} + TEST_F(LedNotificationTest, TestQueueOrder1) { NotifierLedStatus_t status; - for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { - status.queued_priorities[i] = NOTIFY_PRIORITY_BACKGROUND; - } + init(&status, NOTIFY_PRIORITY_BACKGROUND); + insert(&status, NOTIFY_PRIORITY_LOW); + insert(&status, NOTIFY_PRIORITY_CRITICAL); + insert(&status, NOTIFY_PRIORITY_LOW); + insert(&status, NOTIFY_PRIORITY_CRITICAL); - ExtLedNotification_t notification0; - notification0.priority = NOTIFY_PRIORITY_LOW; - push_queued_sequence(¬ification0, &status); - ExtLedNotification_t notification1; - notification1.priority = NOTIFY_PRIORITY_CRITICAL; - push_queued_sequence(¬ification1, &status); - ExtLedNotification_t notification2; - notification2.priority = NOTIFY_PRIORITY_LOW; - push_queued_sequence(¬ification2, &status); - ExtLedNotification_t notification3; - notification3.priority = NOTIFY_PRIORITY_CRITICAL; - push_queued_sequence(¬ification3, &status); EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[0]); EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[1]); EXPECT_EQ(NOTIFY_PRIORITY_CRITICAL, status.queued_priorities[2]); EXPECT_EQ(NOTIFY_PRIORITY_CRITICAL, status.queued_priorities[3]); EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, status.queued_priorities[4]); - } TEST_F(LedNotificationTest, TestQueueOrder2) { @@ -57,13 +57,9 @@ TEST_F(LedNotificationTest, TestQueueOrder2) { // 147 status->queued_sequences[insert_point] = new_notification->sequence; // 148 updated_sequence = insert_point; - for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { - status.queued_priorities[i] = NOTIFY_PRIORITY_LOW; - } + init(&status, NOTIFY_PRIORITY_LOW); - ExtLedNotification_t notification; - notification.priority = NOTIFY_PRIORITY_REGULAR; - push_queued_sequence(¬ification, &status); + insert(&status, NOTIFY_PRIORITY_REGULAR); EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, status.queued_priorities[4]); EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[3]); @@ -76,15 +72,28 @@ TEST_F(LedNotificationTest, TestQueueOrder3) { NotifierLedStatus_t status; // Fails because queued_priorities[0] _LOW and not _REGULAR. I _think_ this is a bug. - for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { - status.queued_priorities[i] = NOTIFY_PRIORITY_REGULAR; - } + init(&status, NOTIFY_PRIORITY_REGULAR); - ExtLedNotification_t notification; - notification.priority = NOTIFY_PRIORITY_LOW; - push_queued_sequence(¬ification, &status); + insert(&status, NOTIFY_PRIORITY_LOW); for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, status.queued_priorities[i]); } } + +TEST_F(LedNotificationTest, TestQueueOrder4) { + NotifierLedStatus_t status; + + init(&status, NOTIFY_PRIORITY_BACKGROUND); + + insert(&status, NOTIFY_PRIORITY_REGULAR); + insert(&status, NOTIFY_PRIORITY_REGULAR); + insert(&status, NOTIFY_PRIORITY_REGULAR); + insert(&status, NOTIFY_PRIORITY_LOW); + + EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, status.queued_priorities[4]); + EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, status.queued_priorities[3]); + EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, status.queued_priorities[2]); + EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, status.queued_priorities[1]); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[0]); +} From cf9329b8ee9bae5cb829bbf1a245a6af5c2ce75c Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Wed, 20 Aug 2014 19:14:03 +0200 Subject: [PATCH 147/203] OP-1440 - Change timing slightly to support also WS2812B --- flight/pios/inc/pios_ws2811_cfg.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/flight/pios/inc/pios_ws2811_cfg.h b/flight/pios/inc/pios_ws2811_cfg.h index d4d7085fb..a4a6b5739 100644 --- a/flight/pios/inc/pios_ws2811_cfg.h +++ b/flight/pios/inc/pios_ws2811_cfg.h @@ -45,8 +45,8 @@ // Following times are keept on the lower side to accounts // for bus contentions and irq response time -#define PIOS_WS2811_T0_HIGH_PERIOD 25 // .35us +/- 150nS -#define PIOS_WS2811_T1_HIGH_PERIOD 60 // .70us +/- 150nS +#define PIOS_WS2811_T0_HIGH_PERIOD 32 // .35us +/- 150nS +#define PIOS_WS2811_T1_HIGH_PERIOD 70 // .70us +/- 150nS #define PIOS_WS2811_DMA_CH1_CONFIG(channel) \ { \ From 436646d070643cda7e479cf540567e7ec553ff58 Mon Sep 17 00:00:00 2001 From: m_thread Date: Sun, 7 Sep 2014 10:15:09 +0200 Subject: [PATCH 148/203] OP-1222 Added configuration code for GPS and Airspeed sensors to the hardware settings section. Still some ?? since the Platinum GPS support not yet is merged to this branch. --- .../vehicleconfigurationhelper.cpp | 78 ++++++++++++++++++- 1 file changed, 77 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 1999b2807..94046b4c8 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -39,6 +39,8 @@ #include "stabilizationsettingsbank1.h" #include "revocalibration.h" #include "accelgyrosettings.h" +#include "gpssettings.h" +#include "airspeedsettings.h" #include const qint16 VehicleConfigurationHelper::LEGACY_ESC_FREQUENCE = 50; @@ -116,6 +118,12 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() HwSettings *hwSettings = HwSettings::GetInstance(m_uavoManager); HwSettings::DataFields data = hwSettings->getData(); + GPSSettings *gpsSettings = NULL; + data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 0; + + AirspeedSettings *airspeedSettings = NULL; + data.OptionalModules[HwSettings::OPTIONALMODULES_AIRSPEED] = 0; + switch (m_configSource->getControllerType()) { case VehicleConfigurationSource::CONTROLLER_CC: case VehicleConfigurationSource::CONTROLLER_CC3D: @@ -160,6 +168,7 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() data.RM_MainPort = HwSettings::RM_MAINPORT_TELEMETRY; data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_DISABLED; + switch (m_configSource->getInputType()) { case VehicleConfigurationSource::INPUT_PWM: data.RM_RcvrPort = HwSettings::RM_RCVRPORT_PWM; @@ -168,7 +177,7 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() data.RM_RcvrPort = HwSettings::RM_RCVRPORT_PPM; break; case VehicleConfigurationSource::INPUT_SBUS: - // We have to set teletry on flexport since s.bus needs the mainport. + // We have to set telemetry on flexport since s.bus needs the mainport. data.RM_MainPort = HwSettings::RM_MAINPORT_SBUS; data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_TELEMETRY; break; @@ -184,10 +193,77 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() default: break; } + + if (m_configSource->getGpsType() != VehicleConfigurationSource::GPS_DISABLED) { + + gpsSettings = GPSSettings::GetInstance(m_uavoManager); + GPSSettings::DataFields gpsData = gpsSettings->getData(); + + switch (m_configSource->getGpsType()) { + case VehicleConfigurationSource::GPS_NMEA: + data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 1; + data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; + data.GPSSpeed = HwSettings::GPSSPEED_57600; + gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_NMEA; + break; + case VehicleConfigurationSource::GPS_UBX: + data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 1; + data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; + data.GPSSpeed = HwSettings::GPSSPEED_57600; + gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_UBX; + break; + case VehicleConfigurationSource::GPS_PLATINUM: + data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 1; + data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; + data.GPSSpeed = HwSettings::GPSSPEED_57600; + //gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_PLATINUM; + break; + default: + data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 0; + break; + } + + gpsSettings->setData(gpsData); + } + + if (m_configSource->getVehicleType() == VehicleConfigurationSource::VEHICLE_FIXEDWING && + m_configSource->getAirspeedType() != VehicleConfigurationSource::AIRSPEED_DISABLED) { + + airspeedSettings = AirspeedSettings::GetInstance(m_uavoManager); + AirspeedSettings::DataFields airspeedData = airspeedSettings->getData(); + + switch (m_configSource->getAirspeedType()) { + case VehicleConfigurationSource::AIRSPEED_ESTIMATE: + data.OptionalModules[HwSettings::OPTIONALMODULES_AIRSPEED] = 1; + airspeedData.AirspeedSensorType = AirspeedSettings::AIRSPEEDSENSORTYPE_GROUNDSPEEDBASEDWINDESTIMATION; + break; + case VehicleConfigurationSource::AIRSPEED_EAGLETREE: + data.OptionalModules[HwSettings::OPTIONALMODULES_AIRSPEED] = 1; + data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_I2C; + airspeedData.AirspeedSensorType = AirspeedSettings::AIRSPEEDSENSORTYPE_EAGLETREEAIRSPEEDV3; + break; + case VehicleConfigurationSource::AIRSPEED_MS4525: + data.OptionalModules[HwSettings::OPTIONALMODULES_AIRSPEED] = 1; + data.RM_FlexiPort = HwSettings::RM_FLEXIPORT_I2C; + airspeedData.AirspeedSensorType = AirspeedSettings::AIRSPEEDSENSORTYPE_PIXHAWKAIRSPEEDMS4525DO; + break; + default: + data.OptionalModules[HwSettings::OPTIONALMODULES_AIRSPEED] = 0; + break; + } + + airspeedSettings->setData(airspeedData); + } break; default: break; } + if (gpsSettings != NULL) { + addModifiedObject(gpsSettings, tr("Writing GPS sensor settings")); + } + if (airspeedSettings != NULL) { + addModifiedObject(airspeedSettings, tr("Writing Airspeed sensor settings")); + } hwSettings->setData(data); addModifiedObject(hwSettings, tr("Writing hardware settings")); } From e9dd37eaf89f2299b44b5933a7249f1f34c0311b Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 7 Sep 2014 12:24:05 +0200 Subject: [PATCH 149/203] OP-1222 Bigger size for wizard window + add margins for connection diagram --- .../src/plugins/setupwizard/connectiondiagram.cpp | 6 +++--- ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp | 4 ++-- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp index 0618e01ac..78dc796e9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -50,14 +50,14 @@ void ConnectionDiagram::resizeEvent(QResizeEvent *event) { QWidget::resizeEvent(event); - ui->connectionDiagram->fitInView(m_scene->itemsBoundingRect(), Qt::KeepAspectRatio); + ui->connectionDiagram->fitInView(m_scene->itemsBoundingRect().adjusted(-5,-5,5,5), Qt::KeepAspectRatio); } void ConnectionDiagram::showEvent(QShowEvent *event) { QWidget::showEvent(event); - ui->connectionDiagram->fitInView(m_scene->itemsBoundingRect(), Qt::KeepAspectRatio); + ui->connectionDiagram->fitInView(m_scene->itemsBoundingRect().adjusted(-5,-5,5,5), Qt::KeepAspectRatio); } void ConnectionDiagram::setupGraphicsScene() @@ -225,7 +225,7 @@ void ConnectionDiagram::setupGraphicsScene() ui->connectionDiagram->setSceneRect(m_scene->itemsBoundingRect()); //ui->connectionDiagram->setSceneRect(m_background); - ui->connectionDiagram->fitInView(m_scene->itemsBoundingRect(), Qt::KeepAspectRatio); + ui->connectionDiagram->fitInView(m_scene->itemsBoundingRect().adjusted(-5,-5,5,5), Qt::KeepAspectRatio); //ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio); qDebug() << "Scene complete"; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 22ec8bbf4..27253afe3 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -65,8 +65,8 @@ SetupWizard::SetupWizard(QWidget *parent) : QWizard(parent), VehicleConfiguratio m_actuatorSettings << actuatorChannelSettings(); } setWizardStyle(QWizard::ModernStyle); - setMinimumSize(600, 450); - resize(600, 450); + setMinimumSize(600, 600); + resize(600, 600); createPages(); } From 1a2bf73969ebd38db8eeaa68e7da1d91410f37cd Mon Sep 17 00:00:00 2001 From: m_thread Date: Sun, 7 Sep 2014 13:50:41 +0200 Subject: [PATCH 150/203] OP-1222 Added constant for image padding. re-factored the firInView into a function. Removed old comments. Fixed background on saved image to be white. Was previous black. --- .../plugins/setupwizard/connectiondiagram.cpp | 22 ++++++++++--------- .../plugins/setupwizard/connectiondiagram.h | 2 ++ 2 files changed, 14 insertions(+), 10 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp index 78dc796e9..7da0ed6a3 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -32,6 +32,7 @@ #include "ui_connectiondiagram.h" const char* ConnectionDiagram::FILE_NAME = ":/setupwizard/resources/connection-diagrams.svg"; +const int ConnectionDiagram::IMAGE_PADDING = 10; ConnectionDiagram::ConnectionDiagram(QWidget *parent, VehicleConfigurationSource *configSource) : QDialog(parent), ui(new Ui::ConnectionDiagram), m_configSource(configSource) @@ -49,15 +50,21 @@ ConnectionDiagram::~ConnectionDiagram() void ConnectionDiagram::resizeEvent(QResizeEvent *event) { QWidget::resizeEvent(event); - - ui->connectionDiagram->fitInView(m_scene->itemsBoundingRect().adjusted(-5,-5,5,5), Qt::KeepAspectRatio); + fitInView(); } void ConnectionDiagram::showEvent(QShowEvent *event) { QWidget::showEvent(event); + fitInView(); +} - ui->connectionDiagram->fitInView(m_scene->itemsBoundingRect().adjusted(-5,-5,5,5), Qt::KeepAspectRatio); +void ConnectionDiagram::fitInView() +{ + ui->connectionDiagram->setSceneRect(m_scene->itemsBoundingRect()); + ui->connectionDiagram->fitInView( + m_scene->itemsBoundingRect().adjusted(-IMAGE_PADDING,-IMAGE_PADDING, IMAGE_PADDING, IMAGE_PADDING), + Qt::KeepAspectRatio); } void ConnectionDiagram::setupGraphicsScene() @@ -222,12 +229,7 @@ void ConnectionDiagram::setupGraphicsScene() } setupGraphicsSceneItems(elementsToShow); - - ui->connectionDiagram->setSceneRect(m_scene->itemsBoundingRect()); - //ui->connectionDiagram->setSceneRect(m_background); - ui->connectionDiagram->fitInView(m_scene->itemsBoundingRect().adjusted(-5,-5,5,5), Qt::KeepAspectRatio); - //ui->connectionDiagram->fitInView(m_background, Qt::KeepAspectRatio); - + fitInView(); qDebug() << "Scene complete"; } } @@ -259,7 +261,7 @@ void ConnectionDiagram::on_saveButton_clicked() { QImage image(2200, 1100, QImage::Format_ARGB32); - image.fill(0); + image.fill(Qt::white); QPainter painter(&image); m_scene->render(&painter); QString fileName = QFileDialog::getSaveFileName(this, tr("Save File"), "", tr("Images (*.png *.xpm *.jpg)")); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.h b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.h index 5e4162a42..238d01b06 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.h @@ -47,8 +47,10 @@ public: explicit ConnectionDiagram(QWidget *parent, VehicleConfigurationSource *configSource); ~ConnectionDiagram(); + void fitInView(); private: static const char *FILE_NAME; + static const int IMAGE_PADDING; Ui::ConnectionDiagram *ui; VehicleConfigurationSource *m_configSource; From 7cd46bdeee47e9d7950ddd8e3c6ae39d971b5977 Mon Sep 17 00:00:00 2001 From: m_thread Date: Sun, 7 Sep 2014 13:52:28 +0200 Subject: [PATCH 151/203] OP-1222 Fixed handling of conflicting configurations. Config is now invalidated if use goes back and make changes introducing conflicts. Added more configuration saving logic. --- .../setupwizard/pages/airspeedpage.cpp | 5 ++++ .../src/plugins/setupwizard/pages/gpspage.cpp | 3 ++ .../setupwizard/pages/selectionpage.cpp | 14 +++++++++ .../plugins/setupwizard/pages/selectionpage.h | 2 ++ .../vehicleconfigurationhelper.cpp | 29 ++++++++++--------- 5 files changed, 40 insertions(+), 13 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index cdba16a24..f135d056b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -46,6 +46,11 @@ void AirSpeedPage::initializePage(VehicleConfigurationSource *settings) // Disable non estimated sensors if ports are taken by receivers setItemDisabled(VehicleConfigurationSource::AIRSPEED_EAGLETREE, true); setItemDisabled(VehicleConfigurationSource::AIRSPEED_MS4525, true); + if (getSelectedItem()->id() == VehicleConfigurationSource::AIRSPEED_EAGLETREE || + getSelectedItem()->id() == VehicleConfigurationSource::AIRSPEED_MS4525) { + // If previously selected invalid sensor, reset to estimated + setSelectedItem(VehicleConfigurationSource::AIRSPEED_ESTIMATE); + } } } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp index e8ed72aaa..a9bd41e8a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/gpspage.cpp @@ -43,6 +43,9 @@ void GpsPage::initializePage(VehicleConfigurationSource *settings) bool GpsPage::validatePage(SelectionItem *selectedItem) { getWizard()->setGpsType((SetupWizard::GPS_TYPE)selectedItem->id()); + if (getWizard()->getGpsType() == SetupWizard::GPS_DISABLED) { + getWizard()->setAirspeedType(VehicleConfigurationSource::AIRSPEED_DISABLED); + } return true; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp index 363a8f80e..75a10a207 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.cpp @@ -130,6 +130,20 @@ void SelectionPage::setItemDisabled(int id, bool disabled) } } +void SelectionPage::setSelectedItem(int id) +{ + for (int i = 0; i < m_selectionItems.count(); i++) { + if (m_selectionItems.at(i)->id() == id) { + ui->typeCombo->setCurrentIndex(i); + } + } +} + +SelectionItem *SelectionPage::getSelectedItem() +{ + return m_selectionItems.at(ui->typeCombo->currentIndex()); +} + SelectionItem::SelectionItem(QString name, QString description, QString shapeId, int id, bool disabled) : m_name(name), m_description(description), m_shapeId(shapeId), m_id(id), m_disabled(disabled) {} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h index 5802f5fd5..9a2126ef1 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h @@ -95,6 +95,8 @@ public: void setTitle(QString title); void setText(QString text); void setItemDisabled(int id, bool disabled); + void setSelectedItem(int id); + SelectionItem *getSelectedItem(); protected: virtual void setupSelection(Selection *selection) = 0; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 94046b4c8..c75627387 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -116,12 +116,10 @@ void VehicleConfigurationHelper::clearModifiedObjects() void VehicleConfigurationHelper::applyHardwareConfiguration() { HwSettings *hwSettings = HwSettings::GetInstance(m_uavoManager); + Q_ASSERT(hwSettings); HwSettings::DataFields data = hwSettings->getData(); - GPSSettings *gpsSettings = NULL; data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 0; - - AirspeedSettings *airspeedSettings = NULL; data.OptionalModules[HwSettings::OPTIONALMODULES_AIRSPEED] = 0; switch (m_configSource->getControllerType()) { @@ -196,7 +194,8 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() if (m_configSource->getGpsType() != VehicleConfigurationSource::GPS_DISABLED) { - gpsSettings = GPSSettings::GetInstance(m_uavoManager); + GPSSettings *gpsSettings = GPSSettings::GetInstance(m_uavoManager); + Q_ASSERT(gpsSettings); GPSSettings::DataFields gpsData = gpsSettings->getData(); switch (m_configSource->getGpsType()) { @@ -215,8 +214,15 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() case VehicleConfigurationSource::GPS_PLATINUM: data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 1; data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; - data.GPSSpeed = HwSettings::GPSSPEED_57600; - //gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_PLATINUM; + data.GPSSpeed = HwSettings::GPSSPEED_115200; + /* + gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_UBLOX; + AuxMagSettings *magSettings = AuxMagSettings::GetInstance(m_uavoManager); + AuxMagSettings::DataFields magsData = magSettings->getData(); + magsData.usage = AuxMagSettings::Both; + magSettings->setData(magsData); + addModifiedObject(magSettings, tr("Writing External Mag sensor settings")); + */ break; default: data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 0; @@ -224,12 +230,14 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() } gpsSettings->setData(gpsData); + addModifiedObject(gpsSettings, tr("Writing GPS sensor settings")); } if (m_configSource->getVehicleType() == VehicleConfigurationSource::VEHICLE_FIXEDWING && m_configSource->getAirspeedType() != VehicleConfigurationSource::AIRSPEED_DISABLED) { - airspeedSettings = AirspeedSettings::GetInstance(m_uavoManager); + AirspeedSettings *airspeedSettings = AirspeedSettings::GetInstance(m_uavoManager); + Q_ASSERT(airspeedSettings); AirspeedSettings::DataFields airspeedData = airspeedSettings->getData(); switch (m_configSource->getAirspeedType()) { @@ -253,17 +261,12 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() } airspeedSettings->setData(airspeedData); + addModifiedObject(airspeedSettings, tr("Writing Airspeed sensor settings")); } break; default: break; } - if (gpsSettings != NULL) { - addModifiedObject(gpsSettings, tr("Writing GPS sensor settings")); - } - if (airspeedSettings != NULL) { - addModifiedObject(airspeedSettings, tr("Writing Airspeed sensor settings")); - } hwSettings->setData(data); addModifiedObject(hwSettings, tr("Writing hardware settings")); } From 39ef7056328ae7411af2763b816fb09b24c4bf41 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 7 Sep 2014 14:25:46 +0200 Subject: [PATCH 152/203] OP-1222 Fix collisions between nmea Gps and fixed wing connectors. --- .../resources/connection-diagrams.svg | 1397 ++++++++--------- 1 file changed, 694 insertions(+), 703 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg index a9baa0b91..485722e69 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -30,13 +30,13 @@ inkscape:window-height="928" id="namedview4616" showgrid="false" - inkscape:zoom="1" - inkscape:cx="638.18066" - inkscape:cy="527.93837" + inkscape:zoom="0.70710678" + inkscape:cx="1013.1906" + inkscape:cy="328.38358" inkscape:window-x="0" inkscape:window-y="27" inkscape:window-maximized="1" - inkscape:current-layer="layer37" + inkscape:current-layer="layer21" fit-margin-top="15" fit-margin-left="15" fit-margin-right="15" @@ -44,7 +44,7 @@ inkscape:snap-grids="true" showguides="false" inkscape:guide-bbox="true" - inkscape:snap-global="false" + inkscape:snap-global="true" inkscape:snap-bbox="true" inkscape:object-paths="true" inkscape:snap-bbox-midpoints="true" @@ -2509,7 +2509,8 @@ x1="1250" y1="1450" x2="1490" - y2="1450" /> + y2="1450" + gradientTransform="translate(225,-90)" /> + y2="1450" + gradientTransform="translate(225,-95)" /> image/svg+xml - + @@ -8972,49 +8974,43 @@ + transform="matrix(0.4,0,0,0.4,-132.525,-98.70912)"> - - - - - - + + + + + transform="matrix(0.4,0,0,0.4,-131.04473,-97.93132)"> - - - - - - + + + + @@ -24155,22 +24146,22 @@ @@ -24247,19 +24238,19 @@ style="fill:#6b6b6b;fill-opacity:1;fill-rule:evenodd;stroke:#000000;stroke-width:0.99199998px;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none" /> @@ -24271,90 +24262,90 @@ style="fill:none;stroke:#000000;stroke-width:0.99212599px;stroke-linecap:butt;stroke-linejoin:miter;stroke-miterlimit:4;stroke-dasharray:none" /> @@ -24372,7 +24363,7 @@ style="fill:#4d4d4d;fill-rule:nonzero" /> @@ -24382,26 +24373,26 @@ sodipodi:nodetypes="ccc" id="path9977" style="opacity:0.6;fill:none;stroke:#ff0000;stroke-width:3;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;marker-start:url(#DotS);marker-end:url(#Arrow2Send)" - d="m 684.6044,148.81326 l 72.17444,0 l 99.49693,-20.7551" + d="M 684.6044,148.81326 L 756.77884,148.81326 L 856.27577,128.05816" stroke-miterlimit="4" inkscape:connector-curvature="0" /> @@ -24464,7 +24455,7 @@ transform="translate(1170.2617,1551.2617)"> @@ -24482,7 +24473,7 @@ transform="translate(977.2441,1551.2617)"> @@ -24510,7 +24501,7 @@ style="fill:url(#linearGradient10058-2)"> @@ -24531,7 +24522,7 @@ transform="translate(1170.2617,1361.2432)"> @@ -24549,7 +24540,7 @@ transform="translate(977.2441,1361.2432)"> @@ -24572,7 +24563,7 @@ id="g5159"> @@ -24598,7 +24589,7 @@ id="g5191"> @@ -24624,7 +24615,7 @@ id="g5223"> @@ -24650,7 +24641,7 @@ id="g5255"> @@ -24676,7 +24667,7 @@ id="g5287"> @@ -24702,7 +24693,7 @@ id="g5319"> @@ -24728,7 +24719,7 @@ id="g5383"> @@ -24739,75 +24730,75 @@ @@ -24845,29 +24836,29 @@ id="g5429"> @@ -24882,7 +24873,7 @@ transform="translate(1823.7813,1443.3135)"> @@ -24899,7 +24890,7 @@ transform="translate(1687.2949,1579.7949)"> @@ -24916,7 +24907,7 @@ transform="translate(1689.418,1308.9482)"> @@ -24933,7 +24924,7 @@ transform="translate(1552.9316,1445.4316)"> @@ -24955,7 +24946,7 @@ id="g5577"> @@ -24981,7 +24972,7 @@ id="g5609"> @@ -25006,7 +24997,7 @@ id="g5641"> @@ -25032,7 +25023,7 @@ id="g5673"> @@ -25057,7 +25048,7 @@ id="g5705"> @@ -25082,7 +25073,7 @@ id="g5737"> @@ -25107,7 +25098,7 @@ id="g5769"> @@ -25132,7 +25123,7 @@ id="g5801"> @@ -25143,68 +25134,68 @@ @@ -25283,7 +25274,7 @@ id="g4307"> @@ -25299,7 +25290,7 @@ transform="translate(2515.9893,1514.8203)"> @@ -25316,7 +25307,7 @@ transform="translate(2355.4863,1607.2334)"> @@ -25333,7 +25324,7 @@ transform="translate(2516.0371,1330.8896)"> @@ -25350,7 +25341,7 @@ transform="translate(2354.9951,1235.6455)"> @@ -25373,7 +25364,7 @@ id="g5929"> @@ -25399,7 +25390,7 @@ id="g5961"> @@ -25425,7 +25416,7 @@ id="g5993"> @@ -25451,7 +25442,7 @@ id="g6025"> @@ -25477,7 +25468,7 @@ id="g6057"> @@ -25503,7 +25494,7 @@ id="g6089"> @@ -25529,7 +25520,7 @@ id="g6121"> @@ -25555,7 +25546,7 @@ id="g6153"> @@ -25566,12 +25557,12 @@ @@ -25608,7 +25599,7 @@ id="g6209"> @@ -25634,7 +25625,7 @@ id="g6241"> @@ -25645,32 +25636,32 @@ @@ -25706,7 +25697,7 @@ id="g6313"> @@ -25732,7 +25723,7 @@ id="g6345"> @@ -25743,76 +25734,76 @@ @@ -25839,12 +25830,12 @@ transform="matrix(2.2864496,0,0,-2.2864496,-2586.624,2782.7411)"> @@ -25853,29 +25844,29 @@ id="g7099"> @@ -25890,7 +25881,7 @@ transform="translate(2538.3311,837.6123)"> @@ -25912,7 +25903,7 @@ id="g7199"> @@ -25937,7 +25928,7 @@ id="g7231"> @@ -25957,7 +25948,7 @@ transform="translate(2538.3311,657.5947)"> @@ -25979,7 +25970,7 @@ id="g7279"> @@ -26004,7 +25995,7 @@ id="g7311"> @@ -26024,7 +26015,7 @@ transform="translate(2538.3252,1017.5234)"> @@ -26046,7 +26037,7 @@ id="g7391"> @@ -26071,7 +26062,7 @@ id="g7359"> @@ -26082,32 +26073,32 @@ @@ -26145,7 +26136,7 @@ id="g7463"> @@ -26171,7 +26162,7 @@ id="g7495"> @@ -26192,7 +26183,7 @@ transform="translate(2056.7451,657.5947)"> @@ -26215,7 +26206,7 @@ id="g7543"> @@ -26240,7 +26231,7 @@ id="g7575"> @@ -26260,7 +26251,7 @@ transform="translate(2056.7471,1017.5234)"> @@ -26283,7 +26274,7 @@ id="g7623"> @@ -26309,7 +26300,7 @@ id="g7655"> @@ -26320,72 +26311,72 @@ @@ -26459,7 +26450,7 @@ id="g4369"> @@ -26484,7 +26475,7 @@ id="g4401"> @@ -26495,39 +26486,39 @@ @@ -26542,7 +26533,7 @@ transform="translate(429.3359,762.3701)"> @@ -26564,7 +26555,7 @@ id="g4477"> @@ -26589,7 +26580,7 @@ id="g4509"> @@ -26600,7 +26591,7 @@ @@ -26636,7 +26627,7 @@ id="g4965"> @@ -26661,7 +26652,7 @@ id="g4997"> @@ -26674,7 +26665,7 @@ id="g7881"> @@ -26689,7 +26680,7 @@ transform="translate(406.8271,782.3682)"> @@ -26711,7 +26702,7 @@ id="g7943"> @@ -26736,7 +26727,7 @@ id="g7975"> @@ -26747,22 +26738,22 @@ @@ -26786,23 +26777,23 @@ style="fill-rule:nonzero"> @@ -26840,7 +26831,7 @@ id="g5162"> @@ -26866,7 +26857,7 @@ id="g5176"> @@ -26877,7 +26868,7 @@ @@ -26915,7 +26906,7 @@ id="g5200"> @@ -26941,7 +26932,7 @@ id="g5214"> @@ -26958,53 +26949,53 @@ style="fill-rule:nonzero"> @@ -27030,7 +27021,7 @@ id="hexa-x"> @@ -27109,7 +27100,7 @@ @@ -27127,7 +27118,7 @@ @@ -27145,7 +27136,7 @@ @@ -27168,7 +27159,7 @@ @@ -27194,7 +27185,7 @@ @@ -27220,7 +27211,7 @@ @@ -27246,7 +27237,7 @@ @@ -27272,7 +27263,7 @@ @@ -27298,7 +27289,7 @@ @@ -27324,7 +27315,7 @@ @@ -27350,7 +27341,7 @@ @@ -27361,12 +27352,12 @@ @@ -27404,7 +27395,7 @@ @@ -27430,7 +27421,7 @@ @@ -27441,32 +27432,32 @@ @@ -27504,7 +27495,7 @@ @@ -27530,7 +27521,7 @@ @@ -27541,53 +27532,53 @@ @@ -27596,28 +27587,28 @@ style="opacity:0.6;fill:none;stroke:#ff0000;stroke-width:7.5;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;marker-start:url(#DotS);marker-end:url(#Arrow2Send)" inkscape:connector-curvature="0" stroke-miterlimit="4" - d="m 470.3229,324.24379 l 34.1726,0.5182 m 107.5,-0.5182 l 288.48736,0 l 81.95096,-90.17068" + d="M 470.3229,324.24379 L 504.4955,324.76199 M 611.9955,324.24379 L 900.48286,324.24379 L 982.43382,234.07311" id="path19792" /> @@ -27633,7 +27624,7 @@ inkscape:groupmode="layer" id="layer32" inkscape:label="flying-wing" - style="display:none"> + style="display:inline"> + d="M 107.091,651.979 L 103.183,631.125" /> + d="M 116.049,650.299 L 112.142,629.445" /> + d="M 120.516,649.463 L 116.608,628.609" /> + d="M 124.981,648.626 L 121.074,627.772" /> + d="M 129.475,647.785 L 125.567,626.928" /> + d="M 133.94,646.948 L 130.033,626.092" /> + d="M 142.898,645.269 L 138.991,624.415" /> + d="M 147.366,644.433 L 143.458,623.579" /> + d="M 160.817,641.912 L 157.057,621.844" /> + d="M 165.282,641.076 L 161.522,621.009" /> + d="M 169.776,640.232 L 166.017,620.166" /> + d="M 174.242,639.396 L 170.482,619.33" /> + d="M 178.707,638.56 L 174.947,618.496" /> + d="M 183.201,637.718 L 179.441,617.654" /> + d="M 187.666,636.882 L 183.906,616.817" /> + d="M 192.159,636.039 L 188.399,615.974" /> + d="M 196.625,635.203 L 192.865,615.137" /> + d="M 201.091,634.366 L 197.331,614.299" /> + d="M 205.583,633.524 L 201.823,613.457" /> + d="M 210.05,632.688 L 206.29,612.623" /> + d="M 214.543,631.846 L 210.783,611.782" /> + d="M 219.009,631.009 L 215.249,610.944" /> + d="M 223.475,630.172 L 219.715,610.108" /> + d="M 227.968,629.33 L 224.209,609.264" /> + d="M 232.434,628.494 L 228.674,608.428" /> + d="M 236.926,627.652 L 233.166,607.584" /> + d="M 241.392,626.815 L 237.633,606.748" /> + d="M 245.858,625.979 L 242.098,605.913" /> + d="M 250.352,625.136 L 246.592,605.073" /> + d="M 254.817,624.3 L 251.058,604.235" /> + d="M 259.31,623.458 L 255.55,603.392" /> + d="M 263.775,622.622 L 260.015,602.555" /> + d="M 268.241,621.784 L 264.482,601.718" /> + d="M 272.735,620.943 L 268.975,600.876" /> + d="M 277.201,620.106 L 273.441,600.038" /> + d="M 151.177,643.718 L 146.518,618.854" /> @@ -27967,13 +27958,13 @@ transform="matrix(-0.86182848,-0.00300837,-0.00369546,1.0586653,726.01496,-689.1904)" id="elevon-right-bg"> + d="M 107.091,651.979 L 103.183,631.125" /> + d="M 116.049,650.299 L 112.142,629.445" /> + d="M 120.516,649.463 L 116.608,628.609" /> + d="M 124.981,648.626 L 121.074,627.772" /> + d="M 129.475,647.785 L 125.567,626.928" /> + d="M 133.94,646.948 L 130.033,626.092" /> + d="M 142.898,645.269 L 138.991,624.415" /> + d="M 147.366,644.433 L 143.458,623.579" /> + d="M 160.817,641.912 L 157.057,621.844" /> + d="M 165.282,641.076 L 161.522,621.009" /> + d="M 169.776,640.232 L 166.017,620.166" /> + d="M 174.242,639.396 L 170.482,619.33" /> + d="M 178.707,638.56 L 174.947,618.496" /> + d="M 183.201,637.718 L 179.441,617.654" /> + d="M 187.666,636.882 L 183.906,616.817" /> + d="M 192.159,636.039 L 188.399,615.974" /> + d="M 196.625,635.203 L 192.865,615.137" /> + d="M 201.091,634.366 L 197.331,614.299" /> + d="M 205.583,633.524 L 201.823,613.457" /> + d="M 210.05,632.688 L 206.29,612.623" /> + d="M 214.543,631.846 L 210.783,611.782" /> + d="M 219.009,631.009 L 215.249,610.944" /> + d="M 223.475,630.172 L 219.715,610.108" /> + d="M 227.968,629.33 L 224.209,609.264" /> + d="M 232.434,628.494 L 228.674,608.428" /> + d="M 236.926,627.652 L 233.166,607.584" /> + d="M 241.392,626.815 L 237.633,606.748" /> + d="M 245.858,625.979 L 242.098,605.913" /> + d="M 250.352,625.136 L 246.592,605.073" /> + d="M 254.817,624.3 L 251.058,604.235" /> + d="M 259.31,623.458 L 255.55,603.392" /> + d="M 263.775,622.622 L 260.015,602.555" /> + d="M 268.241,621.784 L 264.482,601.718" /> + d="M 272.735,620.943 L 268.975,600.876" /> + d="M 277.201,620.106 L 273.441,600.038" /> + d="M 151.177,643.718 L 146.518,618.854" /> @@ -28297,7 +28288,7 @@ id="circle3808-0-9-5" /> @@ -28343,12 +28334,12 @@ @@ -28398,7 +28389,7 @@ id="circle3808-0-9" /> @@ -28464,22 +28455,22 @@ id="g3577-5"> + d="M 388.375,1470.057 H 409.069 C 409.069,1470.057 403.881,1454.799 398.709,1454.682 C 393.533,1454.565 388.375,1470.057 388.375,1470.057 z" /> @@ -28513,19 +28504,19 @@ style="fill:#ffffff;fill-opacity:1;stroke:#000000;stroke-width:0.64670002;stroke-miterlimit:10" inkscape:connector-curvature="0" stroke-miterlimit="10" - d="m 398.002,892.888 c -0.523,-9.188 -0.92,-18.377 -1.326,-27.563 l -0.547,-13.783 l -0.447,-13.782 c -0.135,-4.594 -0.416,-9.188 -0.63,-13.783 c -0.213,-4.595 -0.231,-9.188 -0.033,-13.78 c 0.194,-4.597 0.512,-9.189 0.972,-13.782 c 0.475,-4.596 1.061,-9.189 2.012,-13.784 c 0.055,-0.267 0.248,-0.42 0.432,-0.339 c 0.114,0.053 0.197,0.184 0.23,0.339 c 0.951,4.595 1.537,9.188 2.012,13.784 c 0.46,4.593 0.776,9.188 0.974,13.782 c 0.195,4.594 0.18,9.188 -0.033,13.78 c -0.215,4.596 -0.496,9.189 -0.631,13.783 l -0.446,13.782 l -0.547,13.783 c -0.406,9.188 -0.803,18.378 -1.326,27.563 c -0.016,0.271 -0.176,0.469 -0.359,0.445 c -0.168,-0.02 -0.294,-0.213 -0.307,-0.445 z" + d="M 398.002,892.888 C 397.479,883.7 397.082,874.511 396.676,865.325 L 396.129,851.542 L 395.682,837.76 C 395.547,833.166 395.266,828.572 395.052,823.977 C 394.839,819.382 394.821,814.789 395.019,810.197 C 395.213,805.6 395.531,801.008 395.991,796.415 C 396.466,791.819 397.052,787.226 398.003,782.631 C 398.058,782.364 398.251,782.211 398.435,782.292 C 398.549,782.345 398.632,782.476 398.665,782.631 C 399.616,787.226 400.202,791.819 400.677,796.415 C 401.137,801.008 401.453,805.603 401.651,810.197 C 401.846,814.791 401.831,819.385 401.618,823.977 C 401.403,828.573 401.122,833.166 400.987,837.76 L 400.541,851.542 L 399.994,865.325 C 399.588,874.513 399.191,883.703 398.668,892.888 C 398.652,893.159 398.492,893.357 398.309,893.333 C 398.141,893.313 398.015,893.12 398.002,892.888 z" id="path3769-8" /> + d="M 561.427,641.241 V 661.657" /> + d="M 556.856,641.241 V 661.657" /> + d="M 552.313,641.241 V 661.657" /> + d="M 547.741,641.241 V 661.657" /> + d="M 543.198,641.241 V 661.657" /> + d="M 538.655,641.241 V 661.657" /> + d="M 534.083,641.241 V 661.657" /> + d="M 529.54,641.241 V 661.657" /> + d="M 524.968,641.241 V 661.657" /> + d="M 520.425,641.241 V 661.657" /> + d="M 515.882,641.241 V 661.657" /> + d="M 511.31,641.241 V 661.657" /> + d="M 506.767,641.241 V 661.657" /> + d="M 502.194,641.241 V 661.657" /> + d="M 497.651,641.241 V 661.657" /> + d="M 493.108,641.241 V 661.657" /> + d="M 488.536,641.241 V 661.657" /> + d="M 483.993,641.241 V 661.657" /> + d="M 479.423,641.241 V 661.657" /> + d="M 474.878,641.241 V 661.657" /> + d="M 470.335,641.241 V 661.657" /> + d="M 465.763,641.241 V 661.657" /> + d="M 461.22,641.241 V 661.657" /> + d="M 456.649,641.241 V 661.657" /> + d="M 452.106,641.241 V 661.657" /> + d="M 447.563,641.241 V 661.657" /> + d="M 442.991,641.241 V 661.657" /> + d="M 438.446,641.241 V 661.657" /> + d="M 566.663,636.359 V 661.657" /> + d="M 136.118,661.657 V 640.437" /> + d="M 140.689,661.657 V 640.437" /> + d="M 145.233,661.657 V 640.437" /> + d="M 149.804,661.657 V 640.437" /> + d="M 154.348,661.657 V 640.437" /> + d="M 158.892,661.657 V 640.437" /> + d="M 163.463,661.657 V 640.437" /> + d="M 168.006,661.657 V 640.437" /> + d="M 172.578,661.657 V 640.437" /> + d="M 177.12,661.657 V 640.437" /> + d="M 181.664,661.657 V 640.437" /> + d="M 186.235,661.657 V 640.437" /> + d="M 190.779,661.657 V 640.437" /> + d="M 195.35,661.657 V 640.437" /> + d="M 199.894,661.657 V 640.437" /> + d="M 204.438,661.657 V 640.437" /> + d="M 209.009,661.657 V 640.437" /> + d="M 213.552,661.657 V 640.437" /> + d="M 218.124,661.657 V 640.437" /> + d="M 222.666,661.657 V 640.437" /> + d="M 227.211,661.657 V 640.437" /> @@ -29762,7 +29753,7 @@ @@ -29773,18 +29764,18 @@ style="fill:#ffffff" inkscape:connector-curvature="0" id="path2603_1_" - d="m 241.945,587.856 c -1.388,-0.025 -2.601,0.564 -3.126,2.237 l -4.801,16.212 l 7.724,4.228 l 3.33,-12.644 c 0.946,-1.46 2.325,-0.898 3.777,-0.015 l 11.45,7.539 c 0.992,0.843 1.67,1.972 1.605,3.783 l -0.707,10.026 c -0.145,1.376 -0.974,2.233 -1.628,2.115 l -18.086,-9.822 l -3.199,12.128 l 1.674,0.607 l 2.727,0.989 l 18.065,6.538 c 2.696,0.989 5.107,-1.996 5.195,-6.442 l 0.076,-15.972 c -0.053,-3.922 -1.956,-6.072 -3.859,-7.608 l -15.1,-11.792 c -1.258,-1.031 -3.33,-2.075 -5.117,-2.107 z m -15.039,15.532 l -3.794,14.762 l 2.512,0.736 v -0.004 l 13.567,5.086 l 3.978,-11.537 l -16.263,-9.043 z m 1.961,20.318 l -3.312,11.197 l 8.528,4.692 l 3.446,-13.083 l -8.662,-2.806 z" /> + d="M 241.945,587.856 C 240.557,587.831 239.344,588.42 238.819,590.093 L 234.018,606.305 L 241.742,610.533 L 245.072,597.889 C 246.018,596.429 247.397,596.991 248.849,597.874 L 260.299,605.413 C 261.291,606.256 261.969,607.385 261.904,609.196 L 261.197,619.222 C 261.052,620.598 260.223,621.455 259.569,621.337 L 241.483,611.515 L 238.284,623.643 L 239.958,624.25 L 242.685,625.239 L 260.75,631.777 C 263.446,632.766 265.857,629.781 265.945,625.335 L 266.021,609.363 C 265.968,605.441 264.065,603.291 262.162,601.755 L 247.062,589.963 C 245.804,588.932 243.732,587.888 241.945,587.856 z M 226.906,603.388 L 223.112,618.15 L 225.624,618.886 V 618.882 L 239.191,623.968 L 243.169,612.431 L 226.906,603.388 z M 228.867,623.706 L 225.555,634.903 L 234.083,639.595 L 237.529,626.512 L 228.867,623.706 z" /> + d="M 223.5,607.767 L 221.934,606.882 L 223.309,601.806 L 219.83,599.905 L 212.154,603.16 L 201.567,600.359 L 210.98,606.736 L 214.662,615.553 L 219.433,617.119 L 220.932,611.48 L 222.411,611.713 L 223.5,607.767 z" /> + d="M 411.702,1616.701 V 1618.021 H 413.044 V 1616.701 H 411.702 z M 413.979,1616.701 V 1622.724 V 1622.736 C 413.979,1623.082 414.043,1623.404 414.17,1623.703 C 414.295,1624.002 414.471,1624.264 414.699,1624.484 C 414.926,1624.713 415.189,1624.886 415.488,1625.023 C 415.787,1625.148 416.101,1625.211 416.443,1625.211 H 416.714 V 1623.947 L 416.466,1623.937 C 416.153,1623.914 415.878,1623.785 415.652,1623.556 C 415.548,1623.447 415.466,1623.324 415.404,1623.179 C 415.347,1623.038 415.326,1622.886 415.326,1622.72 V 1616.698 L 413.979,1616.699 L 413.979,1616.699 z M 427.073,1617.373 V 1618.873 H 426.469 V 1620.144 H 427.073 V 1622.749 C 427.073,1623.095 427.135,1623.417 427.261,1623.716 C 427.394,1624.005 427.572,1624.265 427.79,1624.491 C 428.019,1624.72 428.282,1624.893 428.581,1625.021 C 428.88,1625.146 429.202,1625.209 429.548,1625.209 H 430.515 V 1623.938 H 429.56 C 429.232,1623.915 428.96,1623.786 428.749,1623.557 C 428.645,1623.448 428.56,1623.325 428.497,1623.18 C 428.442,1623.039 428.417,1622.887 428.417,1622.733 V 1620.139 H 430.515 V 1619.869 V 1618.867 H 428.417 V 1617.367 H 427.072 L 427.073,1617.377 L 427.073,1617.377 z M 395.865,1619.129 C 395.519,1619.129 395.197,1619.199 394.898,1619.332 C 394.607,1619.459 394.349,1619.635 394.121,1619.863 C 393.893,1620.09 393.712,1620.353 393.587,1620.652 C 393.461,1620.943 393.401,1621.257 393.401,1621.605 V 1625.21 H 394.743 V 1621.616 C 394.743,1621.278 394.861,1620.991 395.097,1620.755 C 395.207,1620.648 395.335,1620.558 395.476,1620.495 C 395.625,1620.432 395.779,1620.403 395.944,1620.403 H 399.057 C 399.221,1620.403 399.378,1620.43 399.52,1620.495 C 399.669,1620.557 399.799,1620.645 399.911,1620.755 C 400.145,1620.991 400.265,1621.278 400.265,1621.616 V 1625.21 H 400.65 H 401.607 H 402.544 V 1627.636 H 403.892 V 1625.21 H 405.021 H 407.802 H 408.296 C 408.634,1625.21 408.956,1625.147 409.255,1625.022 C 409.552,1624.895 409.812,1624.717 410.04,1624.491 C 410.268,1624.263 410.448,1624.005 410.573,1623.716 C 410.7,1623.417 410.759,1623.095 410.759,1622.749 V 1621.618 C 410.759,1621.272 410.7,1620.95 410.573,1620.651 C 410.448,1620.352 410.266,1620.088 410.04,1619.862 C 409.811,1619.633 409.552,1619.458 409.255,1619.331 C 408.956,1619.206 408.634,1619.142 408.296,1619.142 H 405.021 C 404.675,1619.142 404.353,1619.206 404.054,1619.331 C 403.763,1619.458 403.505,1619.634 403.279,1619.862 C 403.05,1620.089 402.871,1620.352 402.736,1620.651 C 402.611,1620.95 402.547,1621.272 402.547,1621.618 V 1623.94 H 401.611 V 1621.618 V 1621.604 C 401.611,1621.256 401.547,1620.942 401.422,1620.651 C 401.297,1620.352 401.119,1620.088 400.893,1619.862 C 400.665,1619.633 400.404,1619.458 400.103,1619.331 C 399.812,1619.198 399.498,1619.128 399.151,1619.128 H 395.865 L 395.865,1619.129 z M 411.702,1619.129 V 1625.213 H 413.044 V 1619.129 H 411.702 z M 368.386,1619.143 C 368.04,1619.143 367.718,1619.207 367.42,1619.332 C 367.121,1619.459 366.863,1619.635 366.643,1619.863 C 366.415,1620.09 366.234,1620.353 366.1,1620.652 C 365.975,1620.951 365.915,1621.273 365.915,1621.619 V 1622.75 C 365.915,1623.096 365.975,1623.418 366.1,1623.717 C 366.234,1624.006 366.415,1624.266 366.643,1624.492 C 366.863,1624.721 367.122,1624.896 367.42,1625.023 C 367.718,1625.148 368.041,1625.211 368.386,1625.211 H 370.841 H 371.653 H 375.074 V 1627.637 H 376.421 V 1625.211 H 377.551 H 377.992 H 380.826 C 381.164,1625.211 381.485,1625.148 381.784,1625.023 C 382.083,1624.896 382.346,1624.718 382.574,1624.492 C 382.802,1624.263 382.978,1624.006 383.104,1623.717 C 383.229,1623.418 383.293,1623.096 383.294,1622.75 V 1621.619 C 383.294,1621.273 383.23,1620.951 383.104,1620.652 C 382.978,1620.353 382.802,1620.089 382.574,1619.863 C 382.346,1619.634 382.083,1619.459 381.784,1619.332 C 381.485,1619.207 381.164,1619.143 380.826,1619.143 H 377.551 C 377.205,1619.143 376.883,1619.207 376.584,1619.332 C 376.293,1619.459 376.035,1619.635 375.807,1619.863 C 375.579,1620.09 375.398,1620.353 375.264,1620.652 C 375.139,1620.951 375.075,1621.273 375.074,1621.619 V 1623.941 H 373.825 C 373.866,1623.867 373.906,1623.793 373.94,1623.714 C 374.066,1623.415 374.13,1623.093 374.13,1622.747 V 1621.616 C 374.13,1621.27 374.066,1620.948 373.94,1620.649 C 373.814,1620.35 373.638,1620.086 373.41,1619.86 C 373.182,1619.631 372.919,1619.456 372.62,1619.329 C 372.321,1619.204 371.999,1619.141 371.653,1619.141 H 368.386 L 368.386,1619.141 z M 386.714,1619.143 C 386.368,1619.143 386.046,1619.207 385.747,1619.332 C 385.449,1619.459 385.19,1619.635 384.97,1619.863 C 384.742,1620.09 384.56,1620.353 384.427,1620.652 C 384.301,1620.943 384.237,1621.257 384.237,1621.605 V 1622.736 C 384.237,1623.082 384.301,1623.404 384.427,1623.703 C 384.56,1624.002 384.742,1624.265 384.97,1624.492 C 385.19,1624.721 385.449,1624.896 385.747,1625.023 C 386.046,1625.148 386.368,1625.211 386.714,1625.211 H 391.711 V 1623.94 H 386.794 C 386.456,1623.94 386.173,1623.823 385.938,1623.586 C 385.852,1623.492 385.775,1623.387 385.713,1623.269 C 385.65,1623.153 385.609,1623.024 385.594,1622.889 H 392.453 V 1621.606 C 392.453,1621.258 392.389,1620.944 392.264,1620.653 C 392.138,1620.353 391.962,1620.09 391.734,1619.864 C 391.506,1619.635 391.242,1619.46 390.944,1619.333 C 390.645,1619.208 390.323,1619.144 389.977,1619.144 H 386.714 L 386.714,1619.143 z M 420.138,1619.143 C 419.792,1619.143 419.47,1619.207 419.171,1619.332 C 418.872,1619.459 418.614,1619.635 418.398,1619.863 C 418.169,1620.09 417.988,1620.353 417.853,1620.652 C 417.726,1620.951 417.667,1621.273 417.667,1621.619 V 1622.75 C 417.667,1623.096 417.726,1623.418 417.853,1623.717 C 417.988,1624.006 418.167,1624.266 418.398,1624.492 C 418.617,1624.721 418.875,1624.896 419.171,1625.023 C 419.47,1625.148 419.792,1625.211 420.138,1625.211 H 423.408 C 423.754,1625.211 424.076,1625.148 424.373,1625.023 C 424.672,1624.896 424.935,1624.718 425.164,1624.492 C 425.393,1624.263 425.568,1624.006 425.693,1623.717 C 425.82,1623.418 425.881,1623.096 425.881,1622.75 V 1621.619 C 425.881,1621.273 425.819,1620.951 425.693,1620.652 C 425.568,1620.353 425.39,1620.089 425.164,1619.863 C 424.935,1619.634 424.672,1619.459 424.373,1619.332 C 424.076,1619.207 423.754,1619.143 423.408,1619.143 H 420.138 z M 368.47,1620.414 H 371.569 C 371.907,1620.414 372.194,1620.531 372.429,1620.768 C 372.539,1620.877 372.627,1621.012 372.69,1621.163 C 372.753,1621.304 372.783,1621.458 372.783,1621.632 V 1622.739 C 372.783,1622.903 372.753,1623.059 372.69,1623.212 C 372.627,1623.353 372.54,1623.483 372.429,1623.591 C 372.194,1623.827 371.907,1623.945 371.569,1623.945 H 371.185 H 368.47 C 368.132,1623.945 367.845,1623.828 367.609,1623.591 C 367.499,1623.484 367.412,1623.355 367.349,1623.212 C 367.286,1623.062 367.256,1622.903 367.256,1622.739 V 1621.632 C 367.256,1621.458 367.286,1621.304 367.349,1621.163 C 367.412,1621.015 367.499,1620.88 367.609,1620.768 C 367.845,1620.531 368.132,1620.414 368.47,1620.414 z M 377.634,1620.414 H 380.733 C 381.071,1620.414 381.358,1620.531 381.594,1620.768 C 381.83,1621.005 381.947,1621.291 381.947,1621.629 V 1622.736 C 381.947,1623.082 381.83,1623.367 381.594,1623.588 C 381.358,1623.824 381.071,1623.942 380.733,1623.942 H 378.416 H 376.421 V 1622.737 V 1622.106 V 1621.627 C 376.421,1621.453 376.451,1621.299 376.514,1621.158 C 376.585,1621.01 376.678,1620.875 376.787,1620.763 C 377.006,1620.531 377.288,1620.414 377.634,1620.414 z M 386.793,1620.414 H 389.896 C 390.234,1620.414 390.521,1620.531 390.757,1620.768 C 390.867,1620.877 390.95,1621.012 391.013,1621.163 C 391.076,1621.304 391.11,1621.458 391.11,1621.622 H 385.579 C 385.579,1621.458 385.613,1621.304 385.676,1621.163 C 385.739,1621.015 385.827,1620.88 385.937,1620.768 C 386.173,1620.531 386.456,1620.414 386.793,1620.414 z M 405.099,1620.414 H 408.201 C 408.539,1620.414 408.826,1620.531 409.058,1620.768 C 409.294,1621.004 409.412,1621.291 409.412,1621.629 V 1622.736 C 409.412,1623.082 409.295,1623.367 409.058,1623.588 C 408.829,1623.818 408.548,1623.936 408.22,1623.942 H 403.886 V 1622.737 V 1622.106 V 1621.627 C 403.886,1621.453 403.915,1621.299 403.978,1621.158 C 404.048,1621.01 404.138,1620.875 404.249,1620.763 C 404.468,1620.531 404.753,1620.414 405.099,1620.414 z M 420.222,1620.414 H 423.324 C 423.662,1620.414 423.949,1620.531 424.181,1620.768 C 424.292,1620.877 424.378,1621.012 424.445,1621.163 C 424.507,1621.304 424.537,1621.458 424.537,1621.632 V 1622.739 C 424.537,1622.903 424.508,1623.059 424.445,1623.212 C 424.381,1623.353 424.295,1623.483 424.181,1623.591 C 423.949,1623.827 423.66,1623.945 423.324,1623.945 H 420.222 C 419.884,1623.945 419.597,1623.828 419.363,1623.591 C 419.254,1623.484 419.166,1623.355 419.101,1623.212 C 419.039,1623.062 419.009,1622.903 419.009,1622.739 V 1621.632 C 419.009,1621.458 419.038,1621.304 419.101,1621.163 C 419.164,1621.015 419.251,1620.88 419.363,1620.768 C 419.597,1620.531 419.884,1620.414 420.222,1620.414 z" /> @@ -30195,147 +30186,147 @@ inkscape:connector-curvature="0" style="fill:none;stroke:#010101;stroke-width:0.29809999;stroke-linecap:round;stroke-linejoin:round" /> @@ -30351,107 +30342,107 @@ transform="translate(0,1008)" id="aileron-left-raster"> @@ -30609,12 +30600,12 @@ id="g3831"> @@ -30706,12 +30697,12 @@ id="g3786"> @@ -30869,12 +30860,12 @@ id="g3869-2"> @@ -30935,12 +30926,12 @@ id="g3895"> @@ -30997,35 +30988,35 @@ Date: Mon, 8 Sep 2014 22:27:02 +0200 Subject: [PATCH 153/203] OP-1222 Added JSon Api embryo. --- .../src/plugins/uavobjects/uavobject.cpp | 15 +++++++++++++++ .../src/plugins/uavobjects/uavobject.h | 9 +++++++++ .../src/plugins/uavobjects/uavobjectfield.cpp | 15 +++++++++++++++ .../src/plugins/uavobjects/uavobjectfield.h | 7 +++++++ 4 files changed, 46 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp index 58483adea..4e32ae91b 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp @@ -532,6 +532,21 @@ void UAVObject::toXML(QXmlStreamWriter *xmlWriter) xmlWriter->writeEndElement(); // object } +void UAVObject::fromXML(QXmlStreamReader *xmlReader) +{ + +} + +void UAVObject::toJson(QJsonObject *jsonObject) +{ + +} + +void UAVObject::fromJson(const QJsonObject *jsonObject) +{ + +} + /** * Emit the transactionCompleted event (used by the UAVTalk plugin) */ diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.h b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.h index 0c81ebd6c..4929386e4 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.h +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.h @@ -38,6 +38,9 @@ #include #include #include +#include +#include + #include "uavobjectfield.h" #define UAVOBJ_ACCESS_SHIFT 0 @@ -129,7 +132,13 @@ public: QString toString(); QString toStringBrief(); QString toStringData(); + void toXML(QXmlStreamWriter *xmlWriter); + void fromXML(QXmlStreamReader *xmlReader); + + void toJson(QJsonObject *jsonObject); + void fromJson(const QJsonObject *jsonObject); + void emitTransactionCompleted(bool success); void emitNewInstance(UAVObject *); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp index 1ab86536a..20d8bf57e 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp @@ -673,6 +673,21 @@ void UAVObjectField::toXML(QXmlStreamWriter *xmlWriter) xmlWriter->writeEndElement(); // field } +void UAVObjectField::fromXML(QXmlStreamReader *xmlReader) +{ + +} + +void UAVObjectField::toJson(QJsonObject *jsonObject) +{ + +} + +void UAVObjectField::fromJson(const QJsonObject *jsonObject) +{ + +} + qint32 UAVObjectField::pack(quint8 *dataOut) { QMutexLocker locker(obj->getMutex()); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h index 778096729..3044c497d 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.h @@ -35,6 +35,8 @@ #include #include #include +#include +#include class UAVObject; @@ -74,7 +76,12 @@ public: bool isInteger(); bool isText(); QString toString(); + void toXML(QXmlStreamWriter *xmlWriter); + void fromXML(QXmlStreamReader *xmlReader); + + void toJson(QJsonObject *jsonObject); + void fromJson(const QJsonObject *jsonObject); bool isWithinLimits(QVariant var, quint32 index, int board = 0); QVariant getMaxLimit(quint32 index, int board = 0); From 4d81aad85d048406f34c7157d76e2e5565488722 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Sun, 14 Sep 2014 18:01:20 +0200 Subject: [PATCH 154/203] OP-1222 FW_Wizard : Modified Sbus Rx on MainPort, added Gps for FlexiPort --- .../resources/connection-diagrams.svg | 4463 ++++++++++++++++- 1 file changed, 4365 insertions(+), 98 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg index 485722e69..6e87da62c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -30,13 +30,13 @@ inkscape:window-height="928" id="namedview4616" showgrid="false" - inkscape:zoom="0.70710678" - inkscape:cx="1013.1906" - inkscape:cy="328.38358" + inkscape:zoom="0.72019231" + inkscape:cx="604.40238" + inkscape:cy="429.88791" inkscape:window-x="0" inkscape:window-y="27" inkscape:window-maximized="1" - inkscape:current-layer="layer21" + inkscape:current-layer="layer8" fit-margin-top="15" fit-margin-left="15" fit-margin-right="15" @@ -2510,7 +2510,7 @@ y1="1450" x2="1490" y2="1450" - gradientTransform="translate(225,-90)" /> + gradientTransform="translate(-240,-90)" /> + y2="1450" + gradientTransform="translate(-151.00134,-881.62884)" /> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -8682,7 +9683,7 @@ inkscape:groupmode="layer" id="layer19" inkscape:label="pwm" - style="display:inline" + style="display:none" sodipodi:insensitive="true"> @@ -8969,12 +9970,12 @@ inkscape:groupmode="layer" id="layer21" inkscape:label="sbus" - style="display:none" + style="display:inline" sodipodi:insensitive="true"> + transform="matrix(0.4,0,0,0.4,53.475,-98.70912)"> + transform="matrix(0.4,0,0,0.4,44.451336,-221.73416)"> - - - - - - + + + + + transform="translate(9.5291677,71.377308)" + style="display:inline"> @@ -12157,10 +13153,33 @@ inkscape:groupmode="layer" id="layer38" inkscape:label="nano-OPGPS-v8-ublox" - style="display:none" - sodipodi:insensitive="true"> + style="display:none"> + + + + - - - - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transform="translate(9.5291677,71.377308)" + style="display:inline"> + points="251.619,467.777 251.619,467.777 251.619,460.783 233.13,460.783 233.13,492.937 251.619,492.937 251.619,485.734 242.74,485.734 242.74,480.095 251.619,480.095 251.619,473.728 242.74,473.728 242.74,467.777 " /> + points="220.283,364.946 253.082,364.946 253.082,454.937 220.283,454.937 220.283,364.946 " /> + points="225.505,370.688 225.505,449.298 247.754,449.298 247.754,370.688 225.505,370.688 " /> + points="251.619,492.937 251.619,485.734 242.74,485.734 242.74,480.095 251.619,480.095 251.619,473.728 242.74,473.728 242.74,467.777 251.619,467.777 251.619,467.777 251.619,460.783 233.13,460.783 233.13,492.937 " /> + points="220.283,454.937 220.283,364.946 220.283,364.946 253.082,364.946 253.082,454.937 " /> + points="247.754,370.688 225.505,370.688 225.505,370.688 225.505,449.298 247.754,449.298 " /> @@ -14997,7 +19264,7 @@ + points="242.74,485.734 242.74,480.095 251.619,480.095 251.619,473.728 242.74,473.728 242.74,467.777 251.619,467.777 251.619,467.777 251.619,460.783 233.13,460.783 233.13,492.937 251.619,492.937 251.619,485.734 " /> + points="251.619,492.937 251.619,485.734 242.74,485.734 242.74,480.095 251.619,480.095 251.619,473.728 242.74,473.728 242.74,467.777 251.619,467.777 251.619,467.777 251.619,460.783 233.13,460.783 233.13,492.937 " /> + points="253.082,454.937 220.283,454.937 220.283,364.946 220.283,364.946 253.082,364.946 " /> + points="247.754,449.298 247.754,370.688 225.505,370.688 225.505,370.688 225.505,449.298 " /> Date: Mon, 15 Sep 2014 22:25:07 +0200 Subject: [PATCH 155/203] OP-1491 HQuad_mixing_values First commit : add QuadH artwork, config tab --- flight/libraries/sanitycheck.c | 1 + .../configmultirotorwidget.cpp | 15 +- .../config/images/multirotor-shapes.svg | 1587 ++++++++++++++++- shared/uavobjectdefinition/systemsettings.xml | 2 +- 4 files changed, 1595 insertions(+), 10 deletions(-) diff --git a/flight/libraries/sanitycheck.c b/flight/libraries/sanitycheck.c index 0902cbce7..7faf4bc08 100644 --- a/flight/libraries/sanitycheck.c +++ b/flight/libraries/sanitycheck.c @@ -262,6 +262,7 @@ FrameType_t GetCurrentFrameType() switch ((SystemSettingsAirframeTypeOptions)airframe_type) { case SYSTEMSETTINGS_AIRFRAMETYPE_QUADX: case SYSTEMSETTINGS_AIRFRAMETYPE_QUADP: + case SYSTEMSETTINGS_AIRFRAMETYPE_QUADH: case SYSTEMSETTINGS_AIRFRAMETYPE_HEXA: case SYSTEMSETTINGS_AIRFRAMETYPE_OCTO: case SYSTEMSETTINGS_AIRFRAMETYPE_OCTOX: diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index e1189d79d..abbd048e8 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -176,6 +176,12 @@ void ConfigMultiRotorWidget::setupUI(QString frameType) m_aircraft->mrRollMixLevel->setValue(50); m_aircraft->mrPitchMixLevel->setValue(50); setYawMixLevel(50); + } else if (frameType == "QuadH" || frameType == "Quad H") { + setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad H")); + + m_aircraft->mrRollMixLevel->setValue(50); + m_aircraft->mrPitchMixLevel->setValue(70); + setYawMixLevel(50); } else if (frameType == "QuadP" || frameType == "Quad +") { setComboCurrentIndex(m_aircraft->multirotorFrameType, m_aircraft->multirotorFrameType->findText("Quad +")); @@ -271,6 +277,8 @@ void ConfigMultiRotorWidget::setupEnabledControls(QString frameType) enableComboBoxes(this, CHANNELBOXNAME, 4, true); } else if (frameType == "QuadP" || frameType == "Quad +") { enableComboBoxes(this, CHANNELBOXNAME, 4, true); + } else if (frameType == "QuadH" || frameType == "Quad H") { + enableComboBoxes(this, CHANNELBOXNAME, 4, true); } else if (frameType == "Hexa" || frameType == "Hexacopter") { enableComboBoxes(this, CHANNELBOXNAME, 6, true); } else if (frameType == "HexaX" || frameType == "Hexacopter X") { @@ -470,6 +478,9 @@ QString ConfigMultiRotorWidget::updateConfigObjectsFromWidgets() } else if (m_aircraft->multirotorFrameType->currentText() == "Quad X") { airframeType = "QuadX"; setupQuad(false); + } else if (m_aircraft->multirotorFrameType->currentText() == "Quad H") { + airframeType = "QuadH"; + setupQuad(false); } else if (m_aircraft->multirotorFrameType->currentText() == "Hexacopter") { airframeType = "Hexa"; setupHexa(true); @@ -743,6 +754,8 @@ void ConfigMultiRotorWidget::updateAirframe(QString frameType) elementId = "quad-x"; } else if (frameType == "QuadP" || frameType == "Quad +") { elementId = "quad-plus"; + } else if (frameType == "QuadH" || frameType == "Quad H") { + elementId = "quad-H"; } else if (frameType == "Hexa" || frameType == "Hexacopter") { elementId = "quad-hexa"; } else if (frameType == "HexaX" || frameType == "Hexacopter X") { @@ -874,7 +887,7 @@ bool ConfigMultiRotorWidget::setupQuad(bool pLayout) setupMotors(motorList); // Now, setup the mixer: - // Motor 1 to 4, X Layout: + // Motor 1 to 4, X Layout and Hlayout // pitch roll yaw // {0.5 ,0.5 ,-0.5 //Front left motor (CW) // {0.5 ,-0.5 ,0.5 //Front right motor(CCW) diff --git a/ground/openpilotgcs/src/plugins/config/images/multirotor-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/multirotor-shapes.svg index fae42213c..a2fa8a514 100644 --- a/ground/openpilotgcs/src/plugins/config/images/multirotor-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/multirotor-shapes.svg @@ -15,7 +15,7 @@ height="3560.019" id="svg4183" xml:space="preserve" - inkscape:version="0.48.4 r9939" + inkscape:version="0.48.5 r10040" sodipodi:docname="multirotor-shapes.svg">image/svg+xml \ No newline at end of file + d="m 3062.2588,1271.4951 l 2.557,0 c 0.279,0 0.5,-0.107 0.695,-0.297 c 0.1,-0.088 0.176,-0.199 0.215,-0.314 c 0.051,-0.118 0.084,-0.246 0.084,-0.387 l 0,-0.914 c 0,-0.135 -0.033,-0.266 -0.084,-0.395 c -0.039,-0.107 -0.115,-0.209 -0.215,-0.298 c -0.195,-0.194 -0.416,-0.299 -0.695,-0.299 l -2.557,0 c -0.275,0 -0.504,0.105 -0.693,0.299 c -0.104,0.089 -0.174,0.191 -0.225,0.298 c -0.039,0.129 -0.078,0.26 -0.078,0.395 l 0,0.914 c 0,0.141 0.039,0.269 0.078,0.387 c 0.051,0.115 0.121,0.226 0.225,0.314 c 0.189,0.19 0.418,0.297 0.693,0.297 m -12.41,0 l 2.558,0 c 0.276,0 0.497,-0.107 0.688,-0.297 c 0.191,-0.187 0.309,-0.426 0.309,-0.701 l 0,-0.914 c 0,-0.277 -0.118,-0.526 -0.309,-0.693 c -0.184,-0.192 -0.41,-0.299 -0.676,-0.299 l -3.566,0 l 0,0.992 l 0,0.521 l 0,0.393 c 0,0.141 0.035,0.269 0.084,0.387 c 0.051,0.115 0.129,0.226 0.228,0.314 c 0.176,0.19 0.403,0.297 0.684,0.297 m -15.022,0 l 2.551,0 c 0.287,0 0.506,-0.107 0.701,-0.297 c 0.096,-0.088 0.166,-0.199 0.213,-0.314 c 0.053,-0.118 0.082,-0.246 0.082,-0.379 l -4.541,0 c 0,0.133 0.033,0.261 0.08,0.379 c 0.051,0.115 0.121,0.226 0.219,0.314 c 0.189,0.19 0.426,0.297 0.695,0.297 m -7.509,0 l 2.537,0 c 0.281,0 0.519,-0.107 0.715,-0.297 c 0.197,-0.187 0.281,-0.426 0.281,-0.701 l 0,-0.914 c 0,-0.277 -0.084,-0.526 -0.281,-0.693 c -0.196,-0.194 -0.434,-0.299 -0.715,-0.299 l -1.893,0 l -1.641,0 l 0,0.992 l 0,0.521 l 0,0.393 c 0,0.141 0.02,0.269 0.073,0.387 c 0.062,0.115 0.135,0.226 0.224,0.314 c 0.18,0.19 0.42,0.297 0.7,0.297 m -7.518,0 l 2.539,0 c 0.277,0 0.522,-0.107 0.709,-0.297 c 0.088,-0.088 0.158,-0.199 0.215,-0.314 c 0.051,-0.118 0.074,-0.246 0.074,-0.387 l 0,-0.914 c 0,-0.135 -0.023,-0.266 -0.074,-0.395 c -0.057,-0.107 -0.127,-0.209 -0.215,-0.298 c -0.187,-0.194 -0.432,-0.299 -0.709,-0.299 l -0.318,0 l -2.221,0 c -0.281,0 -0.514,0.105 -0.713,0.299 c -0.082,0.089 -0.158,0.191 -0.209,0.298 c -0.057,0.129 -0.074,0.26 -0.074,0.395 l 0,0.914 c 0,0.141 0.017,0.269 0.074,0.387 c 0.051,0.115 0.127,0.226 0.209,0.314 c 0.199,0.19 0.432,0.297 0.713,0.297 m 42.391,1.041 c -0.278,0 -0.543,-0.049 -0.795,-0.166 c -0.233,-0.088 -0.453,-0.242 -0.619,-0.42 c -0.194,-0.189 -0.34,-0.406 -0.457,-0.652 c -0.106,-0.254 -0.141,-0.52 -0.141,-0.793 l 0,-0.93 c 0,-0.281 0.035,-0.547 0.141,-0.795 c 0.117,-0.242 0.263,-0.455 0.457,-0.642 c 0.166,-0.178 0.386,-0.332 0.619,-0.426 c 0.252,-0.115 0.517,-0.16 0.795,-0.16 l 2.693,0 c 0.277,0 0.543,0.045 0.791,0.16 c 0.236,0.094 0.459,0.248 0.637,0.426 c 0.189,0.187 0.334,0.4 0.445,0.642 c 0.096,0.248 0.147,0.514 0.147,0.795 l 0,0.93 c 0,0.273 -0.051,0.539 -0.147,0.793 c -0.111,0.246 -0.256,0.463 -0.445,0.652 c -0.178,0.178 -0.401,0.332 -0.637,0.42 c -0.248,0.117 -0.514,0.166 -0.791,0.166 l -2.693,0 z m -27.428,0 c -0.274,0 -0.539,-0.049 -0.797,-0.166 c -0.236,-0.088 -0.451,-0.242 -0.625,-0.42 c -0.186,-0.189 -0.34,-0.406 -0.447,-0.652 c -0.108,-0.252 -0.156,-0.508 -0.156,-0.785 l 0,-0.93 c 0,-0.277 0.048,-0.541 0.156,-0.795 c 0.107,-0.244 0.261,-0.463 0.447,-0.65 c 0.174,-0.178 0.389,-0.332 0.625,-0.426 c 0.258,-0.115 0.523,-0.16 0.797,-0.16 l 4.111,0 l 0,1.039 l -4.047,0 c -0.269,0 -0.506,0.105 -0.695,0.299 c -0.074,0.078 -0.133,0.16 -0.18,0.257 c -0.058,0.096 -0.091,0.203 -0.107,0.303 l 5.627,0 l 0,1.063 c 0,0.277 -0.051,0.533 -0.145,0.785 c -0.117,0.246 -0.254,0.463 -0.449,0.652 c -0.182,0.178 -0.4,0.332 -0.644,0.42 c -0.233,0.117 -0.5,0.166 -0.791,0.166 l -2.68,0 z m -15.031,0 c -0.291,0 -0.555,-0.049 -0.793,-0.166 c -0.25,-0.088 -0.459,-0.242 -0.645,-0.42 c -0.183,-0.189 -0.336,-0.406 -0.445,-0.652 c -0.1,-0.254 -0.153,-0.52 -0.153,-0.793 l 0,-0.93 c 0,-0.281 0.053,-0.547 0.153,-0.795 c 0.109,-0.242 0.262,-0.455 0.445,-0.642 c 0.186,-0.178 0.395,-0.332 0.645,-0.426 c 0.238,-0.115 0.502,-0.16 0.793,-0.16 l 2.011,0 l 0.664,0 l 2.803,0 l 0,-1.989 l 1.111,0 l 0,1.989 l 0.928,0 l 0.36,0 l 2.324,0 c 0.283,0 0.543,0.045 0.783,0.16 c 0.252,0.094 0.463,0.248 0.654,0.426 c 0.192,0.187 0.334,0.4 0.436,0.642 c 0.099,0.248 0.158,0.514 0.158,0.795 l 0,0.93 c 0,0.273 -0.059,0.539 -0.158,0.793 c -0.102,0.246 -0.244,0.463 -0.436,0.652 c -0.191,0.178 -0.402,0.332 -0.654,0.42 c -0.24,0.117 -0.5,0.166 -0.783,0.166 l -2.684,0 c -0.281,0 -0.545,-0.049 -0.793,-0.166 c -0.244,-0.088 -0.455,-0.242 -0.642,-0.42 c -0.186,-0.189 -0.338,-0.406 -0.44,-0.652 c -0.107,-0.254 -0.164,-0.52 -0.164,-0.793 l 0,-1.914 l -1.017,0 c 0.027,0.062 0.068,0.127 0.087,0.189 c 0.112,0.248 0.165,0.514 0.165,0.795 l 0,0.93 c 0,0.273 -0.053,0.539 -0.165,0.793 c -0.091,0.246 -0.244,0.463 -0.423,0.652 c -0.192,0.178 -0.407,0.332 -0.653,0.42 c -0.252,0.117 -0.517,0.166 -0.797,0.166 l -2.675,0 z m 35.543,-4.984 l 1.105,0 l 0,5 l -1.105,0 l 0,-5 z m -13.004,5 c -0.274,0 -0.539,-0.059 -0.791,-0.182 c -0.229,-0.088 -0.446,-0.242 -0.625,-0.42 c -0.186,-0.189 -0.336,-0.406 -0.451,-0.652 c -0.096,-0.252 -0.139,-0.508 -0.139,-0.785 l 0,-2.961 l 1.086,0 l 0,2.953 c 0,0.273 0.113,0.513 0.301,0.707 c 0.08,0.09 0.197,0.158 0.302,0.213 c 0.121,0.052 0.244,0.074 0.381,0.074 l 2.569,0 c 0.132,0 0.263,-0.022 0.369,-0.074 c 0.121,-0.055 0.244,-0.123 0.314,-0.213 c 0.197,-0.194 0.301,-0.434 0.301,-0.707 l 0,-2.953 l 0.307,0 l 0.785,0 l 0.777,0 l 0,-1.989 l 1.096,0 l 0,1.989 l 0.927,0 l 2.299,0 l 0.407,0 c 0.265,0 0.531,0.045 0.783,0.16 c 0.23,0.094 0.451,0.248 0.631,0.426 c 0.183,0.187 0.338,0.4 0.445,0.642 c 0.103,0.248 0.139,0.514 0.139,0.795 l 0,0.93 c 0,0.273 -0.036,0.539 -0.139,0.793 c -0.107,0.246 -0.262,0.463 -0.445,0.652 c -0.18,0.178 -0.401,0.332 -0.631,0.42 c -0.252,0.117 -0.518,0.166 -0.783,0.166 l -2.706,0 c -0.279,0 -0.544,-0.049 -0.792,-0.166 c -0.225,-0.088 -0.438,-0.242 -0.625,-0.42 c -0.19,-0.189 -0.34,-0.406 -0.456,-0.652 c -0.099,-0.254 -0.15,-0.52 -0.15,-0.793 l 0,-1.914 l -0.777,0 l 0,1.914 l 0,0.01 c 0,0.277 -0.053,0.533 -0.139,0.785 c -0.119,0.246 -0.262,0.463 -0.451,0.652 c -0.184,0.178 -0.406,0.332 -0.643,0.42 c -0.23,0.123 -0.496,0.182 -0.777,0.182 l -2.699,0 z m 25.617,1.429 l 0,-1.22 l -0.49,0 l 0,-1.053 l 0.49,0 l 0,-2.133 c 0,-0.281 0.06,-0.547 0.154,-0.795 c 0.112,-0.242 0.252,-0.455 0.438,-0.642 c 0.195,-0.178 0.4,-0.332 0.652,-0.426 c 0.236,-0.115 0.502,-0.16 0.793,-0.16 l 0.791,0 l 0,1.039 l -0.777,0 c -0.27,0.025 -0.504,0.129 -0.664,0.32 c -0.096,0.078 -0.168,0.191 -0.213,0.307 c -0.049,0.105 -0.065,0.232 -0.065,0.365 l 0,2.125 l 1.719,0 l 0,0.223 l 0,0.83 l -1.719,0 l 0,1.22 l -1.109,0 z m -10.752,0.563 l 0,-4.961 c 0,-0.277 0.06,-0.541 0.162,-0.795 c 0.1,-0.244 0.24,-0.463 0.434,-0.639 c 0.197,-0.183 0.398,-0.332 0.66,-0.437 c 0.234,-0.115 0.49,-0.16 0.777,-0.16 l 0.221,0 l 0,1.035 l -0.201,0 c -0.262,0.025 -0.479,0.129 -0.664,0.32 c -0.088,0.078 -0.157,0.191 -0.198,0.307 c -0.064,0.105 -0.068,0.232 -0.068,0.365 l 0,4.961 l -1.123,0 z m -1.861,-1.096 l 1.105,0 l 0,1.096 l -1.105,0 l 0,-1.096 z" /> \ No newline at end of file diff --git a/shared/uavobjectdefinition/systemsettings.xml b/shared/uavobjectdefinition/systemsettings.xml index ae808f185..0b9780597 100644 --- a/shared/uavobjectdefinition/systemsettings.xml +++ b/shared/uavobjectdefinition/systemsettings.xml @@ -1,7 +1,7 @@ Select airframe type. Currently used by @ref ActuatorModule to choose mixing from @ref ActuatorDesired to @ref ActuatorCommand - + -image/svg+xml \ No newline at end of file +image/svg+xml \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 1657ca526..db5b0cd8b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -197,6 +197,9 @@ QString SetupWizard::getSummaryText() case SetupWizard::MULTI_ROTOR_QUAD_PLUS: summary.append(tr("Quadcopter +")); break; + case SetupWizard::MULTI_ROTOR_QUAD_H: + summary.append(tr("Quadcopter H")); + break; case SetupWizard::MULTI_ROTOR_HEXA: summary.append(tr("Hexacopter")); break; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 4fd26406e..d8c83195d 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -198,6 +198,7 @@ void VehicleConfigurationHelper::applyVehicleConfiguration() break; case VehicleConfigurationSource::MULTI_ROTOR_QUAD_X: case VehicleConfigurationSource::MULTI_ROTOR_QUAD_PLUS: + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_H: setupQuadCopter(); break; case VehicleConfigurationSource::MULTI_ROTOR_HEXA: @@ -272,6 +273,7 @@ void VehicleConfigurationHelper::applyActuatorConfiguration() } break; case VehicleConfigurationSource::MULTI_ROTOR_QUAD_X: + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_H: case VehicleConfigurationSource::MULTI_ROTOR_QUAD_PLUS: data.ChannelUpdateFreq[0] = updateFrequence; data.ChannelUpdateFreq[1] = updateFrequence; @@ -487,6 +489,11 @@ void VehicleConfigurationHelper::applyMixerConfiguration(mixerChannelSettings ch mixSettings->setMixerValuePitch(100); mixSettings->setMixerValueYaw(50); break; + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_H: + mixSettings->setMixerValueRoll(50); + mixSettings->setMixerValuePitch(70); + mixSettings->setMixerValueYaw(50); + break; case VehicleConfigurationSource::MULTI_ROTOR_HEXA_COAX_Y: mixSettings->setMixerValueRoll(100); mixSettings->setMixerValuePitch(50); @@ -890,6 +897,44 @@ void VehicleConfigurationHelper::setupQuadCopter() break; } + case VehicleConfigurationSource::MULTI_ROTOR_QUAD_H: + { + frame = SystemSettings::AIRFRAMETYPE_QUADH; + channels[0].type = MIXER_TYPE_MOTOR; + channels[0].throttle1 = 100; + channels[0].throttle2 = 0; + channels[0].roll = 50; + channels[0].pitch = 70; + channels[0].yaw = -50; + + channels[1].type = MIXER_TYPE_MOTOR; + channels[1].throttle1 = 100; + channels[1].throttle2 = 0; + channels[1].roll = -50; + channels[1].pitch = 70; + channels[1].yaw = 50; + + channels[2].type = MIXER_TYPE_MOTOR; + channels[2].throttle1 = 100; + channels[2].throttle2 = 0; + channels[2].roll = -50; + channels[2].pitch = -70; + channels[2].yaw = -50; + + channels[3].type = MIXER_TYPE_MOTOR; + channels[3].throttle1 = 100; + channels[3].throttle2 = 0; + channels[3].roll = 50; + channels[3].pitch = -70; + channels[3].yaw = 50; + + guiSettings.multi.VTOLMotorNW = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorSE = 3; + guiSettings.multi.VTOLMotorSW = 4; + + break; + } default: break; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 797283656..171b7f32a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -57,7 +57,7 @@ public: enum CONTROLLER_TYPE { CONTROLLER_UNKNOWN, CONTROLLER_CC, CONTROLLER_CC3D, CONTROLLER_REVO, CONTROLLER_OPLINK }; enum VEHICLE_TYPE { VEHICLE_UNKNOWN, VEHICLE_MULTI, VEHICLE_FIXEDWING, VEHICLE_HELI, VEHICLE_SURFACE }; - enum VEHICLE_SUB_TYPE { MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS, + enum VEHICLE_SUB_TYPE { MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS, MULTI_ROTOR_QUAD_H, MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_X, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, MULTI_ROTOR_OCTO_X, MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, FIXED_WING_AILERON, FIXED_WING_VTAIL, HELI_CCPM }; From 365a9c5026f11d0f26b5f9dc491c5caaf155a210 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Tue, 16 Sep 2014 01:16:45 +0200 Subject: [PATCH 160/203] OP-1491 HQuad_mixing_values : Wizard fixes, should works now --- .../src/plugins/setupwizard/pages/multipage.cpp | 2 +- .../src/plugins/setupwizard/pages/outputcalibrationpage.cpp | 6 ++++++ 2 files changed, 7 insertions(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp index bb81b1869..55affd185 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp @@ -99,7 +99,7 @@ void MultiPage::setupMultiTypesCombo() "for FPV since the fore rotor tend to be in the way of the camera."); ui->typeCombo->addItem(tr("Quadcopter H"), SetupWizard::MULTI_ROTOR_QUAD_H); - m_descriptions << tr("Quadcopter H, Blackout mini"); + m_descriptions << tr("Quadcopter H, Blackout miniH"); ui->typeCombo->addItem(tr("Hexacopter"), SetupWizard::MULTI_ROTOR_HEXA); m_descriptions << tr("Hexacopter"); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index d40fdb14a..801e706b8 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -80,6 +80,12 @@ void OutputCalibrationPage::setupVehicle() m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4; m_channelIndex << 0 << 0 << 1 << 2 << 3; break; + case SetupWizard::MULTI_ROTOR_QUAD_H: + m_wizardIndexes << 0 << 1 << 1 << 1 << 1; + m_vehicleElementIds << "quad-h" << "quad-h-frame" << "quad-h-m1" << "quad-h-m2" << "quad-h-m3" << "quad-h-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"; From 4bc89ef638b147273b46728d317044420fe36569 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Tue, 16 Sep 2014 01:47:34 +0200 Subject: [PATCH 161/203] OP-1491 HQuad_mixing_values : Renamed with quad-h labels, artwork fixes. --- .../configmultirotorwidget.cpp | 2 +- .../config/images/multirotor-shapes.svg | 858 ++++++------------ .../plugins/setupwizard/pages/multipage.cpp | 2 +- 3 files changed, 284 insertions(+), 578 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index e13e535c3..1b787f935 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -761,7 +761,7 @@ void ConfigMultiRotorWidget::updateAirframe(QString frameType) } else if (frameType == "QuadP" || frameType == "Quad +") { elementId = "quad-plus"; } else if (frameType == "QuadH" || frameType == "Quad H") { - elementId = "quad-H"; + elementId = "quad-h"; } else if (frameType == "Hexa" || frameType == "Hexacopter") { elementId = "quad-hexa"; } else if (frameType == "HexaX" || frameType == "Hexacopter X") { diff --git a/ground/openpilotgcs/src/plugins/config/images/multirotor-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/multirotor-shapes.svg index b601653bf..23df6e045 100644 --- a/ground/openpilotgcs/src/plugins/config/images/multirotor-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/multirotor-shapes.svg @@ -29,16 +29,16 @@ inkscape:window-height="928" id="namedview6635" showgrid="false" - inkscape:zoom="0.62516573" - inkscape:cx="1134.1195" - inkscape:cy="-494.78048" + inkscape:zoom="1.8454215" + inkscape:cx="1126.3879" + inkscape:cy="3502.9988" inkscape:window-x="0" inkscape:window-y="27" inkscape:window-maximized="1" - inkscape:current-layer="quad-H_reverse" + inkscape:current-layer="svg4183" inkscape:object-paths="true" inkscape:snap-midpoints="true" - inkscape:snap-global="false" />image/svg+xml \ No newline at end of file + d="M 976.1062,4029.8127 L 976.1062,4016.1652 L 972.64246,4018.8427 L 970.35745,4015.7189 L 976.47245,4011.2314 L 980.51496,4011.2314 L 980.51496,4029.8127 L 976.1062,4029.8127 z" /> \ No newline at end of file diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp index 55affd185..d3a1a1187 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp @@ -158,7 +158,7 @@ void MultiPage::updateImageAndDescription() elementId = "quad-plus"; break; case SetupWizard::MULTI_ROTOR_QUAD_H: - elementId = "quad-H"; + elementId = "quad-h"; break; case SetupWizard::MULTI_ROTOR_HEXA: elementId = "quad-hexa"; From d0c9e236a1376fae19beef0e3ca31ae338ca1e08 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Tue, 16 Sep 2014 19:01:17 +0200 Subject: [PATCH 162/203] OP-1222 Fix label for quad-h in connection-diagrams.svg --- .../setupwizard/resources/connection-diagrams.svg | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg index b15a2bad7..a43ec2b2e 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -30,13 +30,13 @@ inkscape:window-height="928" id="namedview4616" showgrid="false" - inkscape:zoom="1.0535626" - inkscape:cx="1013.1782" + inkscape:zoom="0.54491305" + inkscape:cx="1013.827" inkscape:cy="514.92134" inkscape:window-x="0" inkscape:window-y="27" inkscape:window-maximized="1" - inkscape:current-layer="g39812" + inkscape:current-layer="layer7" fit-margin-top="15" fit-margin-left="15" fit-margin-right="15" @@ -10289,7 +10289,7 @@ image/svg+xml - + @@ -29307,11 +29307,10 @@ inkscape:groupmode="layer" id="layer7" inkscape:label="quad-h" - style="display:inline" - sodipodi:insensitive="true"> + style="display:inline"> From a8f0bb6eb6b9179da62d578b64cfaf6cc35abafb Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Tue, 16 Sep 2014 19:27:18 +0200 Subject: [PATCH 163/203] OP-1222 Uncrustify --- .../calibration/sixpointcalibrationmodel.cpp | 8 ++--- .../calibration/sixpointcalibrationmodel.h | 4 +-- .../configmultirotorwidget.cpp | 2 +- .../config/configvehicletypewidget.cpp | 2 +- .../plugins/setupwizard/connectiondiagram.cpp | 10 ++++--- .../setupwizard/pages/airspeedpage.cpp | 9 +++--- .../plugins/setupwizard/pages/airspeedpage.h | 1 - .../plugins/setupwizard/pages/multipage.cpp | 2 +- .../plugins/setupwizard/pages/selectionpage.h | 6 ++-- .../resources/connection-diagrams.svg | 15 +++++----- .../src/plugins/setupwizard/setupwizard.cpp | 1 + .../plugins/setupwizard/setupwizardplugin.cpp | 9 +++--- .../vehicleconfigurationhelper.cpp | 29 +++++++++---------- .../src/plugins/uavobjects/uavobject.cpp | 7 +++-- .../src/plugins/uavobjects/uavobjectfield.cpp | 2 +- 15 files changed, 55 insertions(+), 52 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.cpp b/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.cpp index f877a44b5..0593600e0 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.cpp +++ b/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.cpp @@ -101,7 +101,7 @@ SixPointCalibrationModel::SixPointCalibrationModel(QObject *parent) : revoCalibration = RevoCalibration::GetInstance(getObjectManager()); Q_ASSERT(revoCalibration); - auxMagSettings = AuxMagSettings::GetInstance(getObjectManager()); + auxMagSettings = AuxMagSettings::GetInstance(getObjectManager()); Q_ASSERT(auxMagSettings); accelGyroSettings = AccelGyroSettings::GetInstance(getObjectManager()); @@ -440,7 +440,7 @@ void SixPointCalibrationModel::compute() double Be_length; RevoCalibration::DataFields revoCalibrationData = revoCalibration->getData(); - AuxMagSettings::DataFields auxCalibrationData = auxMagSettings->getData(); + AuxMagSettings::DataFields auxCalibrationData = auxMagSettings->getData(); AccelGyroSettings::DataFields accelGyroSettingsData = accelGyroSettings->getData(); HomeLocation::DataFields homeLocationData = homeLocation->getData(); @@ -521,8 +521,8 @@ void SixPointCalibrationModel::compute() if (good_calibration) { m_dirty = true; if (calibratingMag) { - result.revoCalibrationData = revoCalibrationData; - result.auxMagSettingsData = auxCalibrationData; + result.revoCalibrationData = revoCalibrationData; + result.auxMagSettingsData = auxCalibrationData; displayInstructions(tr("Magnetometer calibration completed successfully."), WizardModel::Success); } if (calibratingAccel) { diff --git a/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.h b/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.h index b398aeb0c..464a20de9 100644 --- a/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.h +++ b/ground/openpilotgcs/src/plugins/config/calibration/sixpointcalibrationmodel.h @@ -92,14 +92,14 @@ public: UAVObject::Metadata accelStateMetadata; UAVObject::Metadata magSensorMetadata; UAVObject::Metadata auxMagSensorMetadata; - AuxMagSettings::DataFields auxMagSettings; + AuxMagSettings::DataFields auxMagSettings; RevoCalibration::DataFields revoCalibrationData; AccelGyroSettings::DataFields accelGyroSettingsData; } Memento; typedef struct { RevoCalibration::DataFields revoCalibrationData; - AuxMagSettings::DataFields auxMagSettingsData; + AuxMagSettings::DataFields auxMagSettingsData; AccelGyroSettings::DataFields accelGyroSettingsData; } Result; diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index 8ce2c5167..193269b48 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -137,7 +137,7 @@ ConfigMultiRotorWidget::ConfigMultiRotorWidget(QWidget *parent) : m_aircraft->quadShape->setScene(scene); QStringList multiRotorTypes; - multiRotorTypes << "Tricopter Y" << "Quad +" << "Quad X" << "Quad H" << "Hexacopter" << "Hexacopter X" << "Hexacopter H" + multiRotorTypes << "Tricopter Y" << "Quad +" << "Quad X" << "Quad H" << "Hexacopter" << "Hexacopter X" << "Hexacopter H" << "Hexacopter Y6" << "Octocopter" << "Octocopter X" << "Octocopter V" << "Octo Coax +" << "Octo Coax X"; m_aircraft->multirotorFrameType->addItems(multiRotorTypes); diff --git a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp index 55f06b783..3affbb7b8 100644 --- a/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configvehicletypewidget.cpp @@ -265,7 +265,7 @@ int ConfigVehicleTypeWidget::frameCategory(QString frameType) || frameType == "Elevon" || frameType == "FixedWingVtail" || frameType == "Vtail") { return ConfigVehicleTypeWidget::FIXED_WING; } else if (frameType == "Tri" || frameType == "Tricopter Y" || frameType == "QuadX" || frameType == "Quad X" - || frameType == "QuadP" || frameType == "Quad +" || frameType == "Quad H" || frameType == "QuadH" + || frameType == "QuadP" || frameType == "Quad +" || frameType == "Quad H" || frameType == "QuadH" || frameType == "Hexa" || frameType == "Hexacopter" || frameType == "HexaX" || frameType == "Hexacopter X" || frameType == "HexaCoax" || frameType == "HexaH" || frameType == "Hexacopter H" || frameType == "Hexacopter Y6" diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp index 940319c85..227d851bb 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -31,7 +31,7 @@ #include "connectiondiagram.h" #include "ui_connectiondiagram.h" -const char* ConnectionDiagram::FILE_NAME = ":/setupwizard/resources/connection-diagrams.svg"; +const char *ConnectionDiagram::FILE_NAME = ":/setupwizard/resources/connection-diagrams.svg"; const int ConnectionDiagram::IMAGE_PADDING = 10; ConnectionDiagram::ConnectionDiagram(QWidget *parent, VehicleConfigurationSource *configSource) : @@ -50,12 +50,14 @@ ConnectionDiagram::~ConnectionDiagram() void ConnectionDiagram::resizeEvent(QResizeEvent *event) { QWidget::resizeEvent(event); + fitInView(); } void ConnectionDiagram::showEvent(QShowEvent *event) { QWidget::showEvent(event); + fitInView(); } @@ -63,8 +65,8 @@ void ConnectionDiagram::fitInView() { ui->connectionDiagram->setSceneRect(m_scene->itemsBoundingRect()); ui->connectionDiagram->fitInView( - m_scene->itemsBoundingRect().adjusted(-IMAGE_PADDING,-IMAGE_PADDING, IMAGE_PADDING, IMAGE_PADDING), - Qt::KeepAspectRatio); + m_scene->itemsBoundingRect().adjusted(-IMAGE_PADDING, -IMAGE_PADDING, IMAGE_PADDING, IMAGE_PADDING), + Qt::KeepAspectRatio); } void ConnectionDiagram::setupGraphicsScene() @@ -210,7 +212,7 @@ void ConnectionDiagram::setupGraphicsScene() } if (m_configSource->getVehicleType() == VehicleConfigurationSource::VEHICLE_FIXEDWING && - m_configSource->getAirspeedType() != VehicleConfigurationSource::AIRSPEED_ESTIMATE) { + m_configSource->getAirspeedType() != VehicleConfigurationSource::AIRSPEED_ESTIMATE) { switch (m_configSource->getAirspeedType()) { case VehicleConfigurationSource::AIRSPEED_EAGLETREE: if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index f135d056b..c73989b3e 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -40,14 +40,14 @@ void AirSpeedPage::initializePage(VehicleConfigurationSource *settings) // Enable all setItemDisabled(-1, false); if (settings->getInputType() == VehicleConfigurationSource::INPUT_SBUS || - settings->getInputType() == VehicleConfigurationSource::INPUT_DSM2 || - settings->getInputType() == VehicleConfigurationSource::INPUT_DSMX10 || - settings->getInputType() == VehicleConfigurationSource::INPUT_DSMX11) { + settings->getInputType() == VehicleConfigurationSource::INPUT_DSM2 || + settings->getInputType() == VehicleConfigurationSource::INPUT_DSMX10 || + settings->getInputType() == VehicleConfigurationSource::INPUT_DSMX11) { // Disable non estimated sensors if ports are taken by receivers setItemDisabled(VehicleConfigurationSource::AIRSPEED_EAGLETREE, true); setItemDisabled(VehicleConfigurationSource::AIRSPEED_MS4525, true); if (getSelectedItem()->id() == VehicleConfigurationSource::AIRSPEED_EAGLETREE || - getSelectedItem()->id() == VehicleConfigurationSource::AIRSPEED_MS4525) { + getSelectedItem()->id() == VehicleConfigurationSource::AIRSPEED_MS4525) { // If previously selected invalid sensor, reset to estimated setSelectedItem(VehicleConfigurationSource::AIRSPEED_ESTIMATE); } @@ -90,4 +90,3 @@ void AirSpeedPage::setupSelection(Selection *selection) "ms4525-speed-sensor", SetupWizard::AIRSPEED_MS4525); } - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h index e87838f7a..ff7d1ed2a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h @@ -41,7 +41,6 @@ protected: void initializePage(VehicleConfigurationSource *settings); bool validatePage(SelectionItem *selectedItem); void setupSelection(Selection *selection); - }; #endif // AIRSPEEDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp index f649c7bf1..d1bd8c798 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp @@ -79,7 +79,7 @@ void MultiPage::setupSelection(Selection *selection) selection->addItem(tr("Quadcopter H"), tr("Quadcopter H, Blackout miniH"), "quad-h", - SetupWizard::MULTI_ROTOR_QUAD_H); + SetupWizard::MULTI_ROTOR_QUAD_H); selection->addItem(tr("Hexacopter"), tr("A multirotor with six motors, one motor in front."), diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h index 9a2126ef1..045998d42 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h @@ -58,10 +58,12 @@ public: { return m_id; } - void setDisabled(bool disabled) { + void setDisabled(bool disabled) + { m_disabled = disabled; } - bool disabled() { + bool disabled() + { return m_disabled; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg index a43ec2b2e..fefc1c59a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -26,16 +26,16 @@ guidetolerance="10" inkscape:pageopacity="0" inkscape:pageshadow="2" - inkscape:window-width="1280" - inkscape:window-height="928" + inkscape:window-width="593" + inkscape:window-height="439" id="namedview4616" showgrid="false" - inkscape:zoom="0.54491305" + inkscape:zoom="0.1891554" inkscape:cx="1013.827" inkscape:cy="514.92134" - inkscape:window-x="0" - inkscape:window-y="27" - inkscape:window-maximized="1" + inkscape:window-x="331" + inkscape:window-y="337" + inkscape:window-maximized="0" inkscape:current-layer="layer7" fit-margin-top="15" fit-margin-left="15" @@ -29307,7 +29307,8 @@ inkscape:groupmode="layer" id="layer7" inkscape:label="quad-h" - style="display:inline"> + style="display:inline" + sodipodi:insensitive="true"> addAction(cmd, "Wizard"); cmd = am->registerAction(new QAction(this), - "SetupWizardPlugin.ExportJSon", - QList() << - Core::Constants::C_GLOBAL_ID); + "SetupWizardPlugin.ExportJSon", + QList() << + Core::Constants::C_GLOBAL_ID); cmd->action()->setText(tr("Export Stabilization Settings")); connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportSettings())); @@ -114,12 +114,11 @@ void SetupWizardPlugin::exportSettings() ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); UAVObjectManager *uavoManager = pm->getObject(); - StabilizationSettings* settings = StabilizationSettings::GetInstance(uavoManager); + StabilizationSettings *settings = StabilizationSettings::GetInstance(uavoManager); settings->toJson(exportObject); QJsonDocument saveDoc(exportObject); saveFile.write(saveDoc.toJson()); - } void SetupWizardPlugin::wizardTerminated() diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index b6d8c360a..3840ac16a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -116,6 +116,7 @@ void VehicleConfigurationHelper::clearModifiedObjects() void VehicleConfigurationHelper::applyHardwareConfiguration() { HwSettings *hwSettings = HwSettings::GetInstance(m_uavoManager); + Q_ASSERT(hwSettings); HwSettings::DataFields data = hwSettings->getData(); @@ -193,7 +194,6 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() } if (m_configSource->getGpsType() != VehicleConfigurationSource::GPS_DISABLED) { - GPSSettings *gpsSettings = GPSSettings::GetInstance(m_uavoManager); Q_ASSERT(gpsSettings); GPSSettings::DataFields gpsData = gpsSettings->getData(); @@ -201,28 +201,28 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() switch (m_configSource->getGpsType()) { case VehicleConfigurationSource::GPS_NMEA: data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 1; - data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; - data.GPSSpeed = HwSettings::GPSSPEED_57600; + data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; + data.GPSSpeed = HwSettings::GPSSPEED_57600; gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_NMEA; break; case VehicleConfigurationSource::GPS_UBX: data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 1; - data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; - data.GPSSpeed = HwSettings::GPSSPEED_57600; + data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; + data.GPSSpeed = HwSettings::GPSSPEED_57600; gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_UBX; break; case VehicleConfigurationSource::GPS_PLATINUM: data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 1; data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; - data.GPSSpeed = HwSettings::GPSSPEED_115200; + data.GPSSpeed = HwSettings::GPSSPEED_115200; /* - gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_UBLOX; - AuxMagSettings *magSettings = AuxMagSettings::GetInstance(m_uavoManager); - AuxMagSettings::DataFields magsData = magSettings->getData(); - magsData.usage = AuxMagSettings::Both; - magSettings->setData(magsData); - addModifiedObject(magSettings, tr("Writing External Mag sensor settings")); - */ + gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_UBLOX; + AuxMagSettings *magSettings = AuxMagSettings::GetInstance(m_uavoManager); + AuxMagSettings::DataFields magsData = magSettings->getData(); + magsData.usage = AuxMagSettings::Both; + magSettings->setData(magsData); + addModifiedObject(magSettings, tr("Writing External Mag sensor settings")); + */ break; default: data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 0; @@ -234,8 +234,7 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() } if (m_configSource->getVehicleType() == VehicleConfigurationSource::VEHICLE_FIXEDWING && - m_configSource->getAirspeedType() != VehicleConfigurationSource::AIRSPEED_DISABLED) { - + m_configSource->getAirspeedType() != VehicleConfigurationSource::AIRSPEED_DISABLED) { AirspeedSettings *airspeedSettings = AirspeedSettings::GetInstance(m_uavoManager); Q_ASSERT(airspeedSettings); AirspeedSettings::DataFields airspeedData = airspeedSettings->getData(); diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp index dbf303c88..d72f7dfdc 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp @@ -542,7 +542,7 @@ void UAVObject::fromXML(QXmlStreamReader *xmlReader) Q_ASSERT(xmlReader->attributes().value("name") == getName()); Q_ASSERT(xmlReader->attributes().value("instance") == QString("%1").arg(getInstID())); QXmlStreamReader::TokenType token = xmlReader->readNext(); - if(token == QXmlStreamReader::StartElement && xmlReader->name() == "fields") { + if (token == QXmlStreamReader::StartElement && xmlReader->name() == "fields") { while (xmlReader->readNextStartElement()) { if (xmlReader->name() == "field") { QStringRef fieldName = xmlReader->attributes().value("name"); @@ -556,12 +556,13 @@ void UAVObject::fromXML(QXmlStreamReader *xmlReader) void UAVObject::toJson(QJsonObject &jsonObject) { - jsonObject["name"] = getName(); - jsonObject["id"] = QString("%1").arg(getObjID(), 1, 16).toUpper(); + jsonObject["name"] = getName(); + jsonObject["id"] = QString("%1").arg(getObjID(), 1, 16).toUpper(); jsonObject["instance"] = (int)getInstID(); QJsonArray jSonFields; foreach(UAVObjectField * field, fields) { QJsonObject jSonField; + field->toJson(jSonField); jSonFields.append(jSonField); } diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp index a9eecb5c9..76ab6296c 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp @@ -698,7 +698,7 @@ void UAVObjectField::toJson(QJsonObject &jsonObject) QJsonArray values; for (unsigned int n = 0; n < numElements; ++n) { QJsonObject value; - value["name"] = getElementNames().at(n); + value["name"] = getElementNames().at(n); value["value"] = QJsonValue::fromVariant(getValue(n)); values.append(value); } From b31feb31b33679f86ed6b64bb13dc4beaa7e7f96 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Tue, 16 Sep 2014 20:41:45 +0200 Subject: [PATCH 164/203] OP-1222 FW_Wizard Fix : QuadH and HexaH do not load Svg file --- .../src/plugins/setupwizard/pages/outputcalibrationpage.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp index 9cf8e6dab..a13f97127 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputcalibrationpage.cpp @@ -132,10 +132,12 @@ void OutputCalibrationPage::setupVehicle() setupActuatorMinMaxAndNeutral(0, 3, 4); break; case SetupWizard::MULTI_ROTOR_QUAD_H: + loadSVGFile(MULTI_SVG_FILE); m_wizardIndexes << 0 << 1 << 1 << 1 << 1; m_vehicleElementIds << "quad-h" << "quad-h-frame" << "quad-h-m1" << "quad-h-m2" << "quad-h-m3" << "quad-h-m4"; m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4; m_channelIndex << 0 << 0 << 1 << 2 << 3; + setupActuatorMinMaxAndNeutral(0, 3, 4); break; case SetupWizard::MULTI_ROTOR_QUAD_PLUS: loadSVGFile(MULTI_SVG_FILE); @@ -170,6 +172,7 @@ void OutputCalibrationPage::setupVehicle() setupActuatorMinMaxAndNeutral(0, 5, 6); break; case SetupWizard::MULTI_ROTOR_HEXA_X: + loadSVGFile(MULTI_SVG_FILE); m_wizardIndexes << 0 << 1 << 1 << 1 << 1 << 1 << 1; m_vehicleElementIds << "hexa-x" << "hexa-x-frame" << "hexa-x-m1" << "hexa-x-m2" << "hexa-x-m3" << "hexa-x-m4" << "hexa-x-m5" << "hexa-x-m6"; m_vehicleHighlightElementIndexes << 0 << 1 << 2 << 3 << 4 << 5 << 6; From f500f33326d84b59a4165c8348bb2afd5b633e3c Mon Sep 17 00:00:00 2001 From: m_thread Date: Tue, 16 Sep 2014 23:44:23 +0200 Subject: [PATCH 165/203] OP-1222 Added vehicle template export function. Exports vehicle information and image plus selected settings objects to JSon. Uncrustified. --- .../plugins/setupwizard/connectiondiagram.cpp | 10 +- .../setupwizard/pages/airspeedpage.cpp | 9 +- .../plugins/setupwizard/pages/airspeedpage.h | 1 - .../plugins/setupwizard/pages/selectionpage.h | 6 +- .../src/plugins/setupwizard/setupwizard.cpp | 1 + .../src/plugins/setupwizard/setupwizard.pro | 9 +- .../plugins/setupwizard/setupwizardplugin.cpp | 30 +- .../vehicleconfigurationhelper.cpp | 29 +- .../setupwizard/vehicleconfigurationsource.h | 2 +- .../vehicletemplateexportdialog.cpp | 209 ++++++++ .../setupwizard/vehicletemplateexportdialog.h | 61 +++ .../vehicletemplateexportdialog.ui | 463 ++++++++++++++++++ .../src/plugins/uavobjects/uavobject.cpp | 43 +- .../src/plugins/uavobjects/uavobjectfield.cpp | 2 +- .../plugins/uavobjects/uavobjectmanager.cpp | 57 +++ .../src/plugins/uavobjects/uavobjectmanager.h | 7 + 16 files changed, 865 insertions(+), 74 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui diff --git a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp index 7da0ed6a3..c6f16a01e 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/connectiondiagram.cpp @@ -31,7 +31,7 @@ #include "connectiondiagram.h" #include "ui_connectiondiagram.h" -const char* ConnectionDiagram::FILE_NAME = ":/setupwizard/resources/connection-diagrams.svg"; +const char *ConnectionDiagram::FILE_NAME = ":/setupwizard/resources/connection-diagrams.svg"; const int ConnectionDiagram::IMAGE_PADDING = 10; ConnectionDiagram::ConnectionDiagram(QWidget *parent, VehicleConfigurationSource *configSource) : @@ -50,12 +50,14 @@ ConnectionDiagram::~ConnectionDiagram() void ConnectionDiagram::resizeEvent(QResizeEvent *event) { QWidget::resizeEvent(event); + fitInView(); } void ConnectionDiagram::showEvent(QShowEvent *event) { QWidget::showEvent(event); + fitInView(); } @@ -63,8 +65,8 @@ void ConnectionDiagram::fitInView() { ui->connectionDiagram->setSceneRect(m_scene->itemsBoundingRect()); ui->connectionDiagram->fitInView( - m_scene->itemsBoundingRect().adjusted(-IMAGE_PADDING,-IMAGE_PADDING, IMAGE_PADDING, IMAGE_PADDING), - Qt::KeepAspectRatio); + m_scene->itemsBoundingRect().adjusted(-IMAGE_PADDING, -IMAGE_PADDING, IMAGE_PADDING, IMAGE_PADDING), + Qt::KeepAspectRatio); } void ConnectionDiagram::setupGraphicsScene() @@ -207,7 +209,7 @@ void ConnectionDiagram::setupGraphicsScene() } if (m_configSource->getVehicleType() == VehicleConfigurationSource::VEHICLE_FIXEDWING && - m_configSource->getAirspeedType() != VehicleConfigurationSource::AIRSPEED_ESTIMATE) { + m_configSource->getAirspeedType() != VehicleConfigurationSource::AIRSPEED_ESTIMATE) { switch (m_configSource->getAirspeedType()) { case VehicleConfigurationSource::AIRSPEED_EAGLETREE: if (m_configSource->getControllerType() == VehicleConfigurationSource::CONTROLLER_NANO) { diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp index f135d056b..c73989b3e 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.cpp @@ -40,14 +40,14 @@ void AirSpeedPage::initializePage(VehicleConfigurationSource *settings) // Enable all setItemDisabled(-1, false); if (settings->getInputType() == VehicleConfigurationSource::INPUT_SBUS || - settings->getInputType() == VehicleConfigurationSource::INPUT_DSM2 || - settings->getInputType() == VehicleConfigurationSource::INPUT_DSMX10 || - settings->getInputType() == VehicleConfigurationSource::INPUT_DSMX11) { + settings->getInputType() == VehicleConfigurationSource::INPUT_DSM2 || + settings->getInputType() == VehicleConfigurationSource::INPUT_DSMX10 || + settings->getInputType() == VehicleConfigurationSource::INPUT_DSMX11) { // Disable non estimated sensors if ports are taken by receivers setItemDisabled(VehicleConfigurationSource::AIRSPEED_EAGLETREE, true); setItemDisabled(VehicleConfigurationSource::AIRSPEED_MS4525, true); if (getSelectedItem()->id() == VehicleConfigurationSource::AIRSPEED_EAGLETREE || - getSelectedItem()->id() == VehicleConfigurationSource::AIRSPEED_MS4525) { + getSelectedItem()->id() == VehicleConfigurationSource::AIRSPEED_MS4525) { // If previously selected invalid sensor, reset to estimated setSelectedItem(VehicleConfigurationSource::AIRSPEED_ESTIMATE); } @@ -90,4 +90,3 @@ void AirSpeedPage::setupSelection(Selection *selection) "ms4525-speed-sensor", SetupWizard::AIRSPEED_MS4525); } - diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h index e87838f7a..ff7d1ed2a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airspeedpage.h @@ -41,7 +41,6 @@ protected: void initializePage(VehicleConfigurationSource *settings); bool validatePage(SelectionItem *selectedItem); void setupSelection(Selection *selection); - }; #endif // AIRSPEEDPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h index 9a2126ef1..045998d42 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/selectionpage.h @@ -58,10 +58,12 @@ public: { return m_id; } - void setDisabled(bool disabled) { + void setDisabled(bool disabled) + { m_disabled = disabled; } - bool disabled() { + bool disabled() + { return m_disabled; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 27253afe3..21e8c9124 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -191,6 +191,7 @@ int SetupWizard::nextId() const switch (getVehicleType()) { case VEHICLE_FIXEDWING: return PAGE_OUTPUT_CALIBRATION; + default: return PAGE_BIAS_CALIBRATION; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro index b9e651d3e..d6990971b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.pro @@ -40,7 +40,8 @@ HEADERS += setupwizardplugin.h \ pages/escpage.h \ pages/servopage.h \ pages/selectionpage.h \ - pages/airframeinitialtuningpage.h + pages/airframeinitialtuningpage.h \ + vehicletemplateexportdialog.h SOURCES += setupwizardplugin.cpp \ setupwizard.cpp \ @@ -72,7 +73,8 @@ SOURCES += setupwizardplugin.cpp \ pages/escpage.cpp \ pages/servopage.cpp \ pages/selectionpage.cpp \ - pages/airframeinitialtuningpage.cpp + pages/airframeinitialtuningpage.cpp \ + vehicletemplateexportdialog.cpp OTHER_FILES += SetupWizard.pluginspec @@ -96,7 +98,8 @@ FORMS += \ pages/escpage.ui \ pages/servopage.ui \ pages/selectionpage.ui \ - pages/airframeinitialtuningpage.ui + pages/airframeinitialtuningpage.ui \ + vehicletemplateexportdialog.ui RESOURCES += \ wizardResources.qrc diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp index 544932e9b..39b3d5f0e 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizardplugin.cpp @@ -36,8 +36,7 @@ #include #include #include -#include -#include "stabilizationsettings.h" +#include "vehicletemplateexportdialog.h" SetupWizardPlugin::SetupWizardPlugin() : wizardRunning(false) {} @@ -68,10 +67,10 @@ bool SetupWizardPlugin::initialize(const QStringList & args, QString *errMsg) ac->addAction(cmd, "Wizard"); cmd = am->registerAction(new QAction(this), - "SetupWizardPlugin.ExportJSon", - QList() << - Core::Constants::C_GLOBAL_ID); - cmd->action()->setText(tr("Export Stabilization Settings")); + "SetupWizardPlugin.ExportJSon", + QList() << + Core::Constants::C_GLOBAL_ID); + cmd->action()->setText(tr("Export Wizard Vehicle Template")); connect(cmd->action(), SIGNAL(triggered(bool)), this, SLOT(exportSettings())); Core::ModeManager::instance()->addAction(cmd, 1); @@ -79,7 +78,6 @@ bool SetupWizardPlugin::initialize(const QStringList & args, QString *errMsg) ac->appendGroup("Wizard"); ac->addAction(cmd, "Wizard"); - return true; } @@ -103,23 +101,9 @@ void SetupWizardPlugin::showSetupWizard() void SetupWizardPlugin::exportSettings() { - QFile saveFile(QStringLiteral("/home/fredrik/export.json")); - - if (!saveFile.open(QIODevice::WriteOnly)) { - qWarning("Couldn't open save file."); - return; - } - - QJsonObject exportObject; - - ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); - UAVObjectManager *uavoManager = pm->getObject(); - StabilizationSettings* settings = StabilizationSettings::GetInstance(uavoManager); - settings->toJson(exportObject); - - QJsonDocument saveDoc(exportObject); - saveFile.write(saveDoc.toJson()); + VehicleTemplateExportDialog dialog; + dialog.exec(); } void SetupWizardPlugin::wizardTerminated() diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index c75627387..edbf65aea 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -116,6 +116,7 @@ void VehicleConfigurationHelper::clearModifiedObjects() void VehicleConfigurationHelper::applyHardwareConfiguration() { HwSettings *hwSettings = HwSettings::GetInstance(m_uavoManager); + Q_ASSERT(hwSettings); HwSettings::DataFields data = hwSettings->getData(); @@ -193,7 +194,6 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() } if (m_configSource->getGpsType() != VehicleConfigurationSource::GPS_DISABLED) { - GPSSettings *gpsSettings = GPSSettings::GetInstance(m_uavoManager); Q_ASSERT(gpsSettings); GPSSettings::DataFields gpsData = gpsSettings->getData(); @@ -201,28 +201,28 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() switch (m_configSource->getGpsType()) { case VehicleConfigurationSource::GPS_NMEA: data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 1; - data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; - data.GPSSpeed = HwSettings::GPSSPEED_57600; + data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; + data.GPSSpeed = HwSettings::GPSSPEED_57600; gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_NMEA; break; case VehicleConfigurationSource::GPS_UBX: data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 1; - data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; - data.GPSSpeed = HwSettings::GPSSPEED_57600; + data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; + data.GPSSpeed = HwSettings::GPSSPEED_57600; gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_UBX; break; case VehicleConfigurationSource::GPS_PLATINUM: data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 1; data.RM_MainPort = HwSettings::RM_MAINPORT_GPS; - data.GPSSpeed = HwSettings::GPSSPEED_115200; + data.GPSSpeed = HwSettings::GPSSPEED_115200; /* - gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_UBLOX; - AuxMagSettings *magSettings = AuxMagSettings::GetInstance(m_uavoManager); - AuxMagSettings::DataFields magsData = magSettings->getData(); - magsData.usage = AuxMagSettings::Both; - magSettings->setData(magsData); - addModifiedObject(magSettings, tr("Writing External Mag sensor settings")); - */ + gpsData.DataProtocol = GPSSettings::DATAPROTOCOL_UBLOX; + AuxMagSettings *magSettings = AuxMagSettings::GetInstance(m_uavoManager); + AuxMagSettings::DataFields magsData = magSettings->getData(); + magsData.usage = AuxMagSettings::Both; + magSettings->setData(magsData); + addModifiedObject(magSettings, tr("Writing External Mag sensor settings")); + */ break; default: data.OptionalModules[HwSettings::OPTIONALMODULES_GPS] = 0; @@ -234,8 +234,7 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() } if (m_configSource->getVehicleType() == VehicleConfigurationSource::VEHICLE_FIXEDWING && - m_configSource->getAirspeedType() != VehicleConfigurationSource::AIRSPEED_DISABLED) { - + m_configSource->getAirspeedType() != VehicleConfigurationSource::AIRSPEED_DISABLED) { AirspeedSettings *airspeedSettings = AirspeedSettings::GetInstance(m_uavoManager); Q_ASSERT(airspeedSettings); AirspeedSettings::DataFields airspeedData = airspeedSettings->getData(); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index ccc6ba433..96a7a3dd7 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -60,7 +60,7 @@ public: enum VEHICLE_SUB_TYPE { MULTI_ROTOR_UNKNOWN, MULTI_ROTOR_TRI_Y, MULTI_ROTOR_QUAD_X, MULTI_ROTOR_QUAD_PLUS, MULTI_ROTOR_HEXA, MULTI_ROTOR_HEXA_H, MULTI_ROTOR_HEXA_X, MULTI_ROTOR_HEXA_COAX_Y, MULTI_ROTOR_OCTO, MULTI_ROTOR_OCTO_X, MULTI_ROTOR_OCTO_V, MULTI_ROTOR_OCTO_COAX_X, MULTI_ROTOR_OCTO_COAX_PLUS, - FIXED_WING_DUAL_AILERON, FIXED_WING_AILERON, FIXED_WING_ELEVON, HELI_CCPM }; + FIXED_WING_DUAL_AILERON, FIXED_WING_AILERON, FIXED_WING_ELEVON, FIXED_WING_VTAIL, HELI_CCPM }; enum ESC_TYPE { ESC_RAPID, ESC_STANDARD, ESC_UNKNOWN }; enum SERVO_TYPE { SERVO_ANALOG, SERVO_DIGITAL, SERVO_UNKNOWN }; enum INPUT_TYPE { INPUT_PWM, INPUT_PPM, INPUT_SBUS, INPUT_DSMX10, INPUT_DSMX11, INPUT_DSM2, INPUT_UNKNOWN }; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp new file mode 100644 index 000000000..9e94aea2e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp @@ -0,0 +1,209 @@ +/** + ****************************************************************************** + * + * @file vehicletemplateexportdialog.cpp + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup [Group] + * @{ + * @addtogroup VehicleTemplateExportDialog + * @{ + * @brief [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 "vehicletemplateexportdialog.h" +#include "ui_vehicletemplateexportdialog.h" +#include +#include "systemsettings.h" +#include +#include +#include +#include +#include +#include "stabilizationsettings.h" +#include "stabilizationsettingsbank1.h" +#include "stabilizationsettingsbank2.h" +#include "stabilizationsettingsbank3.h" +#include "ekfconfiguration.h" + +VehicleTemplateExportDialog::VehicleTemplateExportDialog(QWidget *parent) : + QDialog(parent), + ui(new Ui::VehicleTemplateExportDialog) +{ + ui->setupUi(this); + connect(ui->ImportButton, SIGNAL(clicked()), this, SLOT(importImage())); + ExtensionSystem::PluginManager *pm = ExtensionSystem::PluginManager::instance(); + m_uavoManager = pm->getObject(); + ui->Photo->setScene(new QGraphicsScene(this)); + ui->Type->setText(setupVehicleType()); +} + +VehicleTemplateExportDialog::~VehicleTemplateExportDialog() +{ + delete ui; +} + +QString VehicleTemplateExportDialog::setupVehicleType() +{ + SystemSettings *systemSettings = SystemSettings::GetInstance(m_uavoManager); + + Q_ASSERT(systemSettings); + SystemSettings::DataFields systemSettingsData = systemSettings->getData(); + + switch (systemSettingsData.AirframeType) { + case SystemSettings::AIRFRAMETYPE_FIXEDWING: + m_type = VehicleConfigurationSource::VEHICLE_FIXEDWING; + m_subType = VehicleConfigurationSource::FIXED_WING_AILERON; + return tr("Fixed Wing - Aileron"); + + case SystemSettings::AIRFRAMETYPE_FIXEDWINGELEVON: + m_type = VehicleConfigurationSource::VEHICLE_FIXEDWING; + m_subType = VehicleConfigurationSource::FIXED_WING_ELEVON; + return tr("Fixed Wing - Elevon"); + + case SystemSettings::AIRFRAMETYPE_FIXEDWINGVTAIL: + m_type = VehicleConfigurationSource::VEHICLE_FIXEDWING; + m_subType = VehicleConfigurationSource::FIXED_WING_VTAIL; + return tr("Fixed Wing - V-Tail"); + + case SystemSettings::AIRFRAMETYPE_HELICP: + m_type = VehicleConfigurationSource::VEHICLE_HELI; + m_subType = VehicleConfigurationSource::HELI_CCPM; + return tr("Helicopter"); + + case SystemSettings::AIRFRAMETYPE_TRI: + m_type = VehicleConfigurationSource::VEHICLE_MULTI; + m_subType = VehicleConfigurationSource::MULTI_ROTOR_TRI_Y; + return tr("Multirotor - Tricopter"); + + case SystemSettings::AIRFRAMETYPE_QUADX: + m_type = VehicleConfigurationSource::VEHICLE_MULTI; + m_subType = VehicleConfigurationSource::MULTI_ROTOR_QUAD_X; + return tr("Multirotor - Quadrocopter X"); + + case SystemSettings::AIRFRAMETYPE_QUADP: + m_type = VehicleConfigurationSource::VEHICLE_MULTI; + m_subType = VehicleConfigurationSource::MULTI_ROTOR_QUAD_PLUS; + return tr("Multirotor - Quadrocopter +"); + + case SystemSettings::AIRFRAMETYPE_OCTOV: + m_type = VehicleConfigurationSource::VEHICLE_MULTI; + m_subType = VehicleConfigurationSource::MULTI_ROTOR_OCTO_V; + return tr("Multirotor - Octocopter V"); + + case SystemSettings::AIRFRAMETYPE_OCTOCOAXX: + m_type = VehicleConfigurationSource::VEHICLE_MULTI; + m_subType = VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X; + return tr("Multirotor - Octocopter X8X"); + + case SystemSettings::AIRFRAMETYPE_OCTOCOAXP: + m_type = VehicleConfigurationSource::VEHICLE_MULTI; + m_subType = VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_PLUS; + return tr("Multirotor - Octocopter X8+"); + + case SystemSettings::AIRFRAMETYPE_OCTO: + m_type = VehicleConfigurationSource::VEHICLE_MULTI; + m_subType = VehicleConfigurationSource::MULTI_ROTOR_OCTO; + return tr("Multirotor - Octocopter +"); + + case SystemSettings::AIRFRAMETYPE_OCTOX: + m_type = VehicleConfigurationSource::VEHICLE_MULTI; + m_subType = VehicleConfigurationSource::MULTI_ROTOR_OCTO_X; + return tr("Multirotor - Octocopter X"); + + case SystemSettings::AIRFRAMETYPE_HEXAX: + m_type = VehicleConfigurationSource::VEHICLE_MULTI; + m_subType = VehicleConfigurationSource::MULTI_ROTOR_HEXA_X; + return tr("Multirotor - Hexacopter X"); + + case SystemSettings::AIRFRAMETYPE_HEXACOAX: + m_type = VehicleConfigurationSource::VEHICLE_MULTI; + m_subType = VehicleConfigurationSource::MULTI_ROTOR_HEXA_COAX_Y; + return tr("Multirotor - Hexacopter Y6"); + + case SystemSettings::AIRFRAMETYPE_HEXA: + m_type = VehicleConfigurationSource::VEHICLE_MULTI; + m_subType = VehicleConfigurationSource::MULTI_ROTOR_HEXA; + return tr("Multirotor - Hexacopter +"); + + default: + m_type = VehicleConfigurationSource::VEHICLE_UNKNOWN; + return tr("Unsupported"); + } +} + + +void VehicleTemplateExportDialog::accept() +{ + QString fileName = QFileDialog::getSaveFileName(this, tr("Export template"), "", tr("Template (*.optmpl)")); + + if (!fileName.isEmpty()) { + if (!fileName.endsWith(".optmpl")) { + fileName += ".optmpl"; + } + QFile saveFile(fileName); + if (saveFile.open(QIODevice::WriteOnly)) { + QJsonObject exportObject; + + QList objectsToExport; + objectsToExport << StabilizationSettings::GetInstance(m_uavoManager); + objectsToExport << StabilizationSettingsBank1::GetInstance(m_uavoManager); + objectsToExport << StabilizationSettingsBank2::GetInstance(m_uavoManager); + objectsToExport << StabilizationSettingsBank3::GetInstance(m_uavoManager); + objectsToExport << EKFConfiguration::GetInstance(m_uavoManager); + m_uavoManager->toJson(exportObject, objectsToExport); + + exportObject["type"] = m_type; + exportObject["subtype"] = m_subType; + exportObject["name"] = ui->Name->text(); + exportObject["owner"] = ui->Owner->text(); + exportObject["nick"] = ui->ForumNick->text(); + exportObject["size"] = ui->Size->text(); + exportObject["weight"] = ui->Weight->text(); + exportObject["motor"] = ui->Motor->text(); + exportObject["esc"] = ui->Esc->text(); + exportObject["servo"] = ui->Servo->text(); + exportObject["battery"] = ui->Battery->text(); + exportObject["propeller"] = ui->Propeller->text(); + exportObject["controller"] = ui->Controllers->currentText(); + exportObject["comment"] = ui->Comment->document()->toPlainText(); + + QByteArray bytes; + QBuffer buffer(&bytes); + buffer.open(QIODevice::WriteOnly); + m_image.save(&buffer, "PNG"); + exportObject["photo"] = bytes.toBase64().data(); + + QJsonDocument saveDoc(exportObject); + saveFile.write(saveDoc.toJson()); + saveFile.close(); + } + } + QDialog::accept(); +} + +void VehicleTemplateExportDialog::importImage() +{ + QString fileName = QFileDialog::getOpenFileName(this, tr("Import Image"), "", tr("Images (*.png *.jpg)")); + + if (!fileName.isEmpty()) { + m_image.load(fileName); + ui->Photo->scene()->addPixmap(m_image); + ui->Photo->setSceneRect(ui->Photo->scene()->itemsBoundingRect()); + ui->Photo->fitInView(ui->Photo->scene()->itemsBoundingRect(), Qt::KeepAspectRatio); + } +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h new file mode 100644 index 000000000..99af7751b --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h @@ -0,0 +1,61 @@ +/** + ****************************************************************************** + * + * @file vehicletemplateexportdialog.h + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @addtogroup [Group] + * @{ + * @addtogroup VehicleTemplateExportDialog + * @{ + * @brief [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 VEHICLETEMPLATEEXPORTDIALOG_H +#define VEHICLETEMPLATEEXPORTDIALOG_H + +#include +#include "uavobjectmanager.h" +#include "vehicleconfigurationsource.h" + +namespace Ui { +class VehicleTemplateExportDialog; +} + +class VehicleTemplateExportDialog : public QDialog { + Q_OBJECT + +public: + explicit VehicleTemplateExportDialog(QWidget *parent = 0); + ~VehicleTemplateExportDialog(); + +public slots: + void accept(); + +private slots: + void importImage(); + +private: + Ui::VehicleTemplateExportDialog *ui; + UAVObjectManager *m_uavoManager; + QString setupVehicleType(); + VehicleConfigurationSource::VEHICLE_TYPE m_type; + VehicleConfigurationSource::VEHICLE_SUB_TYPE m_subType; + QPixmap m_image; +}; + +#endif // VEHICLETEMPLATEEXPORTDIALOG_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui new file mode 100644 index 000000000..0d5f2e0f3 --- /dev/null +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui @@ -0,0 +1,463 @@ + + + VehicleTemplateExportDialog + + + Qt::ApplicationModal + + + + 0 + 0 + 610 + 700 + + + + + 610 + 700 + + + + + 610 + 700 + + + + Vehicle Template Export + + + false + + + true + + + + + + QFrame::NoFrame + + + QFrame::Raised + + + + 0 + + + 0 + + + 0 + + + 0 + + + + + + 0 + 0 + + + + QFrame::NoFrame + + + QFrame::Plain + + + + 0 + + + 0 + + + 0 + + + 0 + + + + + Weight: + + + + + + + Size and angle + + + + + + + Battery: + + + + + + + Size of the vehicle in mm + + + + + + + Motor: + + + + + + + Name: + + + + + + + Servo: + + + + + + + Brand and name + + + + + + + Your name + + + + + + + Propeller: + + + + + + + Forum name: + + + + + + + Qt::Horizontal + + + + + + + The name of the vehicle, brand etc + + + + + + + Owner: + + + + + + + Brand, size and Kv + + + + + + + Size: + + + + + + + How many cells etc? + + + + + + + Controller: + + + + + + + false + + + background-color: rgba(255, 255, 255, 0); + + + false + + + true + + + + + + + ESC: + + + + + + + + None + + + + + CC + + + + + CC3D + + + + + Atom + + + + + Revolution + + + + + Nano + + + + + + + + Type: + + + + + + + Forum nickname + + + + + + + Brand and name + + + + + + + Weight in grams + + + + + + + + + + + + + QFrame::NoFrame + + + QFrame::Raised + + + + 0 + + + 0 + + + 0 + + + 0 + + + + + Comment: + + + + + + + + 0 + 0 + + + + Qt::ScrollBarAlwaysOn + + + Qt::ScrollBarAlwaysOff + + + Put comments here that doesn't fit in the categories above + + + + + + + + + + QFrame::NoFrame + + + QFrame::Raised + + + + 0 + + + 0 + + + 0 + + + 0 + + + + + Photo: + + + + + + + background-color: rgba(254, 254, 254, 0); + + + QFrame::NoFrame + + + + + 0 + 0 + 0 + + + + + false + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + Import... + + + + + + + + + + Qt::Horizontal + + + QDialogButtonBox::Cancel|QDialogButtonBox::Save + + + + + + + + + buttonBox + accepted() + VehicleTemplateExportDialog + accept() + + + 248 + 254 + + + 157 + 274 + + + + + buttonBox + rejected() + VehicleTemplateExportDialog + reject() + + + 316 + 260 + + + 286 + 274 + + + + + diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp index dbf303c88..c68fbd517 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobject.cpp @@ -538,16 +538,17 @@ void UAVObject::fromXML(QXmlStreamReader *xmlReader) { // Check that we are the correct object by name, and that we are the same instance id // but dont check id since we want to be able to be forward compatible. - Q_ASSERT(xmlReader->name() == "object"); - Q_ASSERT(xmlReader->attributes().value("name") == getName()); - Q_ASSERT(xmlReader->attributes().value("instance") == QString("%1").arg(getInstID())); - QXmlStreamReader::TokenType token = xmlReader->readNext(); - if(token == QXmlStreamReader::StartElement && xmlReader->name() == "fields") { - while (xmlReader->readNextStartElement()) { - if (xmlReader->name() == "field") { - QStringRef fieldName = xmlReader->attributes().value("name"); - if (fieldName != "") { - getField(*fieldName.string())->fromXML(xmlReader); + if (xmlReader->name() == "object" && + xmlReader->attributes().value("name") == getName() && + xmlReader->attributes().value("instance") == QString("%1").arg(getInstID())) { + QXmlStreamReader::TokenType token = xmlReader->readNext(); + if (token == QXmlStreamReader::StartElement && xmlReader->name() == "fields") { + while (xmlReader->readNextStartElement()) { + if (xmlReader->name() == "field") { + QStringRef fieldName = xmlReader->attributes().value("name"); + if (fieldName != "") { + getField(*fieldName.string())->fromXML(xmlReader); + } } } } @@ -556,12 +557,14 @@ void UAVObject::fromXML(QXmlStreamReader *xmlReader) void UAVObject::toJson(QJsonObject &jsonObject) { - jsonObject["name"] = getName(); + jsonObject["name"] = getName(); + jsonObject["setting"] = isSettingsObject(); jsonObject["id"] = QString("%1").arg(getObjID(), 1, 16).toUpper(); jsonObject["instance"] = (int)getInstID(); QJsonArray jSonFields; foreach(UAVObjectField * field, fields) { QJsonObject jSonField; + field->toJson(jSonField); jSonFields.append(jSonField); } @@ -570,15 +573,17 @@ void UAVObject::toJson(QJsonObject &jsonObject) void UAVObject::fromJson(const QJsonObject &jsonObject) { - Q_ASSERT(jsonObject["name"].toString() == getName()); - Q_ASSERT(jsonObject["instance"].toInt() == (int)getInstID()); - QJsonArray jsonFields = jsonObject["fields"].toArray(); - for (int i = 0; i < jsonFields.size(); i++) { - QJsonObject jsonField = jsonFields.at(i).toObject(); - UAVObjectField *field = getField(jsonField["name"].toString()); - if (field) { - field->fromJson(jsonField); + if (jsonObject["name"].toString() == getName() && + jsonObject["instance"].toInt() == (int)getInstID()) { + QJsonArray jsonFields = jsonObject["fields"].toArray(); + for (int i = 0; i < jsonFields.size(); i++) { + QJsonObject jsonField = jsonFields.at(i).toObject(); + UAVObjectField *field = getField(jsonField["name"].toString()); + if (field != NULL) { + field->fromJson(jsonField); + } } + updated(); } } diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp index a9eecb5c9..76ab6296c 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectfield.cpp @@ -698,7 +698,7 @@ void UAVObjectField::toJson(QJsonObject &jsonObject) QJsonArray values; for (unsigned int n = 0; n < numElements; ++n) { QJsonObject value; - value["name"] = getElementNames().at(n); + value["name"] = getElementNames().at(n); value["value"] = QJsonValue::fromVariant(getValue(n)); values.append(value); } diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.cpp index 4b556b2cd..8683f905b 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.cpp @@ -27,6 +27,8 @@ */ #include "uavobjectmanager.h" +#include + /** * Constructor */ @@ -296,6 +298,61 @@ qint32 UAVObjectManager::getNumInstances(quint32 objId) return getNumInstances(NULL, objId); } +void UAVObjectManager::toJson(QJsonObject &jsonObject, UAVObjectManager::JSON_EXPORT_OPTION what) +{ + QList objects; + QList< QList > allObjects = getObjects(); + foreach(QList instances, allObjects) { + foreach(UAVObject * object, instances) { + if (what == JSON_EXPORT_ALL || + (what == JSON_EXPORT_DATA && !object->isSettingsObject()) || + (what == JSON_EXPORT_SETTINGS && object->isSettingsObject()) || + (what == JSON_EXPORT_SETTINGS && object->isMetaDataObject())) { + objects << object; + } + } + } + toJson(jsonObject, objects); +} + +void UAVObjectManager::toJson(QJsonObject &jsonObject, const QList &objectsToExport) +{ + QList objects; + foreach(QString objectName, objectsToExport) { + QList instances = getObjectInstances(objectName); + foreach(UAVObject * object, instances) { + objects << object; + } + } + toJson(jsonObject, objects); +} + +void UAVObjectManager::toJson(QJsonObject &jsonObject, const QList &objectsToExport) +{ + QJsonArray jObjects; + + foreach(UAVObject * object, objectsToExport) { + QJsonObject jObject; + + object->toJson(jObject); + jObjects.append(jObject); + } + jsonObject["objects"] = jObjects; +} + +void UAVObjectManager::fromJson(const QJsonObject &jsonObject) +{ + QJsonArray jObjects = jsonObject["objects"].toArray(); + + for (int i = 0; i < jObjects.size(); i++) { + QJsonObject jObject = jObjects.at(i).toObject(); + UAVObject *object = getObject(jObject["name"].toString(), jObject["instance"].toInt()); + if (object != NULL) { + object->fromJson(jObject); + } + } +} + /** * Helper function for public getNumInstances */ diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.h b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.h index a7fbfdb31..cc6460abe 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.h +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.h @@ -35,11 +35,13 @@ #include #include #include +#include class UAVOBJECTS_EXPORT UAVObjectManager : public QObject { Q_OBJECT public: + enum JSON_EXPORT_OPTION { JSON_EXPORT_ALL, JSON_EXPORT_METADATA, JSON_EXPORT_SETTINGS, JSON_EXPORT_DATA }; UAVObjectManager(); ~UAVObjectManager(); @@ -54,6 +56,11 @@ public: qint32 getNumInstances(const QString & name); qint32 getNumInstances(quint32 objId); + void toJson(QJsonObject &jsonObject, JSON_EXPORT_OPTION what = JSON_EXPORT_ALL); + void toJson(QJsonObject &jsonObject, const QList &objectsToExport); + void toJson(QJsonObject &jsonObject, const QList &objectsToExport); + void fromJson(const QJsonObject &jsonObject); + signals: void newObject(UAVObject *obj); void newInstance(UAVObject *obj); From 1a06822e55c9a5a4fa1bd21c1cef71b898e71df3 Mon Sep 17 00:00:00 2001 From: m_thread Date: Tue, 16 Sep 2014 23:51:36 +0200 Subject: [PATCH 166/203] OP-1222 Changed name of button to select image for the template. --- .../src/plugins/setupwizard/vehicletemplateexportdialog.ui | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui index 0d5f2e0f3..2a1fd7613 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui @@ -406,7 +406,7 @@ - Import... + Select Image... From 46ef59f1865717deb9b2f42dee6d81ec027f8e91 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Wed, 17 Sep 2014 01:24:01 +0200 Subject: [PATCH 167/203] OP-1379 - Rebuild and simplify the queuing mechanism --- flight/libraries/inc/optypes.h | 4 +- flight/libraries/lednotification.c | 110 +++++++++------------- flight/libraries/optypes.c | 1 + flight/modules/Notify/notify.c | 18 ---- flight/tests/lednotification/unittest.cpp | 90 ++++++++++++++---- 5 files changed, 123 insertions(+), 100 deletions(-) diff --git a/flight/libraries/inc/optypes.h b/flight/libraries/inc/optypes.h index 82a95e52e..6b9080db7 100644 --- a/flight/libraries/inc/optypes.h +++ b/flight/libraries/inc/optypes.h @@ -33,6 +33,7 @@ typedef struct { } Color_t; extern const Color_t Color_Off; +extern const Color_t Color_Black; extern const Color_t Color_Red; extern const Color_t Color_Lime; extern const Color_t Color_Blue; @@ -46,7 +47,8 @@ extern const Color_t Color_Teal; extern const Color_t Color_Orange; extern const Color_t Color_White; -#define COLOR_OFF { .R = 0x00, .G = 0x00, .B = 0x00 } +#define COLOR_BLACK { .R = 0x00, .G = 0x00, .B = 0x00 } +#define COLOR_OFF COLOR_BLACK #define COLOR_RED { .R = 0xFF, .G = 0x00, .B = 0x00 } #define COLOR_LIME { .R = 0x00, .G = 0xFF, .B = 0x00 } #define COLOR_BLUE { .R = 0x00, .G = 0x00, .B = 0xFF } diff --git a/flight/libraries/lednotification.c b/flight/libraries/lednotification.c index 4b5950d17..e6d961747 100644 --- a/flight/libraries/lednotification.c +++ b/flight/libraries/lednotification.c @@ -35,19 +35,18 @@ // Private defines // Maximum number of notifications enqueued when a higher priority notification is added -#define MAX_BACKGROUND_NOTIFICATIONS 5 +#define MAX_BACKGROUND_NOTIFICATIONS 6 #define MAX_HANDLED_LED 1 -#define BACKGROUND_SEQUENCE -1 +#define BACKGROUND_SEQUENCE 0 #define RESET_STEP -1 #define GET_CURRENT_MILLIS (xTaskGetTickCount() * portTICK_RATE_MS) // Private data types definition // this is the status for a single notification led set typedef struct { - int8_t queued_priorities[MAX_BACKGROUND_NOTIFICATIONS]; - LedSequence_t queued_sequences[MAX_BACKGROUND_NOTIFICATIONS]; - LedSequence_t background_sequence; + int8_t queued_priorities[MAX_BACKGROUND_NOTIFICATIONS]; // slot 0 is reserved for background + LedSequence_t queued_sequences[MAX_BACKGROUND_NOTIFICATIONS]; // slot 0 is reserved for background uint32_t next_run_time; uint32_t sequence_starting_time; @@ -100,74 +99,62 @@ static void restart_sequence(NotifierLedStatus_t *status, bool immediate) */ static void push_queued_sequence(ExtLedNotification_t *new_notification, NotifierLedStatus_t *status) { - int8_t updated_sequence = BACKGROUND_SEQUENCE; + int8_t updated_sequence; + + int8_t lowest_priority_index = -1; + int8_t lowest_priority = new_notification->priority; if (new_notification->priority == NOTIFY_PRIORITY_BACKGROUND) { - status->background_sequence = new_notification->sequence; + lowest_priority_index = BACKGROUND_SEQUENCE; } else { - // a notification with priority higher than background. - // try to enqueue it - int8_t insert_point = MAX_BACKGROUND_NOTIFICATIONS - 1; - int8_t first_free = -1; - for (int8_t i = MAX_BACKGROUND_NOTIFICATIONS - 1; i >= 0; i--) { - const int8_t priority_i = status->queued_priorities[i]; - if (priority_i == NOTIFY_PRIORITY_BACKGROUND) { - first_free = i; - insert_point = i; - continue; - } - if (priority_i > new_notification->priority) { - insert_point = ((i > 0) || (first_free > -1)) ? i : -1; // check whether priority is no bigger than lowest queued priority + // slot 0 is reserved for Background sequence + for (int8_t i = 1; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { + if (status->queued_priorities[i] < lowest_priority) { + lowest_priority_index = i; + lowest_priority = status->queued_priorities[i]; } } - - // no space left on queue for this new notification, ignore. - if (insert_point < 0) { - return; - } - if (insert_point != first_free) { - // there is a free slot, move everything up one place - if (first_free != -1) { - for (uint8_t i = MAX_BACKGROUND_NOTIFICATIONS - 1; i > insert_point; i--) { - status->queued_priorities[i] = status->queued_priorities[i - 1]; - status->queued_sequences[i] = status->queued_sequences[i - 1]; - } - if (status->active_sequence_num >= insert_point) { - status->active_sequence_num++; - } - } else { - // no free space, discard lowest priority notification and move everything down - for (uint8_t i = 0; i < insert_point; i++) { - status->queued_priorities[i] = status->queued_priorities[i + 1]; - status->queued_sequences[i] = status->queued_sequences[i + 1]; - } - if (status->active_sequence_num <= insert_point) { - status->active_sequence_num--; - } - } - } - - status->queued_priorities[insert_point] = new_notification->priority; - status->queued_sequences[insert_point] = new_notification->sequence; - updated_sequence = insert_point; } - if (status->active_sequence_num < updated_sequence) { + // no items with priority lower than the one we are trying to enqueue. skip + if (lowest_priority_index < 0) { + return; + } + + status->queued_priorities[lowest_priority_index] = new_notification->priority; + status->queued_sequences[lowest_priority_index] = new_notification->sequence; + updated_sequence = lowest_priority_index;; + + + // check whether we should preempt the current notification and play this new one + if (status->queued_priorities[status->active_sequence_num] < new_notification->priority) { status->active_sequence_num = updated_sequence; - restart_sequence(status, true); } - if (updated_sequence == BACKGROUND_SEQUENCE) { - restart_sequence(status, false); + + if (status->active_sequence_num == updated_sequence) { + restart_sequence(status, true); } } static bool pop_queued_sequence(NotifierLedStatus_t *status) { - if (status->active_sequence_num != BACKGROUND_SEQUENCE) { - // start the lower priority item + if (status->active_sequence_num > BACKGROUND_SEQUENCE) { + // set the last active slot as empty status->queued_priorities[status->active_sequence_num] = NOTIFY_PRIORITY_BACKGROUND; - status->active_sequence_num--; - return true; + + // search the highest priority item + int8_t highest_priority_index = BACKGROUND_SEQUENCE; + int8_t highest_priority = NOTIFY_PRIORITY_BACKGROUND; + + for (int8_t i = 1; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { + if (status->queued_priorities[i] > highest_priority) { + highest_priority_index = i; + highest_priority = status->queued_priorities[i]; + } + } + // set the next sequence to activate (or BACKGROUND_SEQUENCE when all slots are empty) + status->active_sequence_num = highest_priority_index; + return highest_priority_index != BACKGROUND_SEQUENCE; } // background sequence was completed return false; @@ -178,9 +165,7 @@ static bool pop_queued_sequence(NotifierLedStatus_t *status) */ static void advance_sequence(NotifierLedStatus_t *status) { - LedSequence_t *activeSequence = - status->active_sequence_num == BACKGROUND_SEQUENCE ? - &status->background_sequence : &status->queued_sequences[status->active_sequence_num]; + LedSequence_t *activeSequence = &status->queued_sequences[status->active_sequence_num]; uint8_t step = status->next_sequence_step; LedStep_t *currentStep = &activeSequence->steps[step]; @@ -244,8 +229,7 @@ static void run_led(NotifierLedStatus_t *status) status->next_run_time = currentTime; uint8_t step = status->next_sequence_step; - LedSequence_t *activeSequence = status->active_sequence_num == BACKGROUND_SEQUENCE ? - &status->background_sequence : &status->queued_sequences[status->active_sequence_num]; + LedSequence_t *activeSequence = &status->queued_sequences[status->active_sequence_num]; const Color_t color = status->step_phase_on ? activeSequence->steps[step].color : Color_Off; for (uint8_t i = status->led_set_start; i <= status->led_set_end; i++) { diff --git a/flight/libraries/optypes.c b/flight/libraries/optypes.c index b67b81c3f..3b2c7b728 100644 --- a/flight/libraries/optypes.c +++ b/flight/libraries/optypes.c @@ -27,6 +27,7 @@ #include const Color_t Color_Off = COLOR_OFF; +const Color_t Color_Black = COLOR_BLACK; const Color_t Color_Red = COLOR_RED; const Color_t Color_Lime = COLOR_LIME; const Color_t Color_Blue = COLOR_BLUE; diff --git a/flight/modules/Notify/notify.c b/flight/modules/Notify/notify.c index 8ccb3cdc4..aeb7526bf 100644 --- a/flight/modules/Notify/notify.c +++ b/flight/modules/Notify/notify.c @@ -24,24 +24,6 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ -/** - * Input objects: ExampleObject1, ExampleSettings - * Output object: ExampleObject2 - * - * This module executes in response to ExampleObject1 updates. When the - * module is triggered it will update the data of ExampleObject2. - * - * No threads are used in this example. - * - * UAVObjects are automatically generated by the UAVObjectGenerator from - * the object definition XML file. - * - * Modules have no API, all communication to other modules is done through UAVObjects. - * However modules may use the API exposed by shared libraries. - * See the OpenPilot wiki for more details. - * http://www.openpilot.org/OpenPilot_Application_Architecture - * - */ #include "openpilot.h" #include #include diff --git a/flight/tests/lednotification/unittest.cpp b/flight/tests/lednotification/unittest.cpp index 3d289ffec..853d4b9f8 100644 --- a/flight/tests/lednotification/unittest.cpp +++ b/flight/tests/lednotification/unittest.cpp @@ -16,6 +16,32 @@ void PIOS_WS2811_Update() {} class LedNotificationTest : public testing::Test {}; +int compare_int8(const void *a, const void *b) +{ + const int8_t *da = (const int8_t *)a; + const int8_t *db = (const int8_t *)b; + + return (*da > *db) - (*da < *db); +} + + +void sort_priorities(int8_t *queued_priorities) +{ + qsort(queued_priorities, MAX_BACKGROUND_NOTIFICATIONS, sizeof(int8_t), compare_int8); +} + +void set_highest_active(NotifierLedStatus_t *status) +{ + int8_t highest = NOTIFY_PRIORITY_BACKGROUND; + + for (int i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { + if (status->queued_priorities[i] > highest) { + status->active_sequence_num = i; + highest = status->queued_priorities[i]; + } + } +} + void insert(NotifierLedStatus_t *status, pios_notify_priority priority) { ExtLedNotification_t notification; @@ -41,12 +67,18 @@ TEST_F(LedNotificationTest, TestQueueOrder1) { insert(&status, NOTIFY_PRIORITY_LOW); insert(&status, NOTIFY_PRIORITY_CRITICAL); + set_highest_active(&status); - EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[0]); - EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[1]); - EXPECT_EQ(NOTIFY_PRIORITY_CRITICAL, status.queued_priorities[2]); - EXPECT_EQ(NOTIFY_PRIORITY_CRITICAL, status.queued_priorities[3]); - EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, status.queued_priorities[4]); + + EXPECT_EQ(NOTIFY_PRIORITY_CRITICAL, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_CRITICAL, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, (status.queued_priorities[status.active_sequence_num])); } TEST_F(LedNotificationTest, TestQueueOrder2) { @@ -58,26 +90,40 @@ TEST_F(LedNotificationTest, TestQueueOrder2) { // 148 updated_sequence = insert_point; init(&status, NOTIFY_PRIORITY_LOW); + status.queued_priorities[0] = NOTIFY_PRIORITY_BACKGROUND; insert(&status, NOTIFY_PRIORITY_REGULAR); - EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, status.queued_priorities[4]); - EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[3]); - EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[2]); - EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[1]); - EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[0]); + set_highest_active(&status); + + EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, (status.queued_priorities[status.active_sequence_num])); } TEST_F(LedNotificationTest, TestQueueOrder3) { NotifierLedStatus_t status; - // Fails because queued_priorities[0] _LOW and not _REGULAR. I _think_ this is a bug. + // Fails because queued_priorities[0] _LOW and not _REGULAR. I _thibnk_ this is a bug. init(&status, NOTIFY_PRIORITY_REGULAR); + status.queued_priorities[0] = NOTIFY_PRIORITY_BACKGROUND; insert(&status, NOTIFY_PRIORITY_LOW); - for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS; i++) { - EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, status.queued_priorities[i]); + set_highest_active(&status); + + + for (uint8_t i = 0; i < MAX_BACKGROUND_NOTIFICATIONS - 1; i++) { + EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); } } @@ -91,9 +137,17 @@ TEST_F(LedNotificationTest, TestQueueOrder4) { insert(&status, NOTIFY_PRIORITY_REGULAR); insert(&status, NOTIFY_PRIORITY_LOW); - EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, status.queued_priorities[4]); - EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, status.queued_priorities[3]); - EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, status.queued_priorities[2]); - EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, status.queued_priorities[1]); - EXPECT_EQ(NOTIFY_PRIORITY_LOW, status.queued_priorities[0]); + set_highest_active(&status); + + EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_REGULAR, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_LOW, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, (status.queued_priorities[status.active_sequence_num])); + pop_queued_sequence(&status); + EXPECT_EQ(NOTIFY_PRIORITY_BACKGROUND, (status.queued_priorities[status.active_sequence_num])); } From 81b2224b7b4aa579e23a3ec86235ebdbe1cd8dc3 Mon Sep 17 00:00:00 2001 From: abeck70 Date: Wed, 17 Sep 2014 21:33:02 +1000 Subject: [PATCH 168/203] OSX Qt5.3.2 changes to tools.mk --- make/tools.mk | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/make/tools.mk b/make/tools.mk index 779ac6798..86ff73da8 100644 --- a/make/tools.mk +++ b/make/tools.mk @@ -76,12 +76,12 @@ ifeq ($(UNAME), Linux) else ifeq ($(UNAME), Darwin) ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-mac.tar.bz2 ARM_SDK_MD5_URL:= https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-mac.tar.bz2/+md5 - QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-mac-x64-clang-5.3.1.dmg - QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-mac-x64-clang-5.3.1.dmg.md5 + QT_SDK_URL := http://qtmirror.ics.com/pub/qtproject/archive/qt/5.3/5.3.2/qt-opensource-mac-x64-clang-5.3.2.dmg + QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.2/qt-opensource-mac-x64-clang-5.3.2.dmg.md5 QT_SDK_ARCH := clang_64 - QT_SDK_MAINTENANCE_TOOL := /Volumes/qt-opensource-mac-x64-clang-5.3.1/qt-opensource-mac-x64-clang-5.3.1.app/Contents/MacOS/qt-opensource-mac-x64-clang-5.3.1 - QT_SDK_MOUNT_DIR := /Volumes/qt-opensource-mac-x64-clang-5.3.1 - QT_SDK_INSTALLER_DAT := /Volumes/qt-opensource-mac-x64-clang-5.3.1/qt-opensource-mac-x64-clang-5.3.1.app/Contents/Resources/installer.dat + QT_SDK_MAINTENANCE_TOOL := /Volumes/qt-opensource-mac-x64-clang-5.3.2/qt-opensource-mac-x64-clang-5.3.2.app/Contents/MacOS/qt-opensource-mac-x64-clang-5.3.2 + QT_SDK_MOUNT_DIR := /Volumes/qt-opensource-mac-x64-clang-5.3.2 + QT_SDK_INSTALLER_DAT := /Volumes/qt-opensource-mac-x64-clang-5.3.2/qt-opensource-mac-x64-clang-5.3.2.app/Contents/Resources/installer.dat UNCRUSTIFY_URL := http://wiki.openpilot.org/download/attachments/18612236/uncrustify-0.60.tar.gz DOXYGEN_URL := http://wiki.openpilot.org/download/attachments/18612236/doxygen-1.8.3.1.src.tar.gz else ifeq ($(UNAME), Windows) @@ -103,7 +103,7 @@ GTEST_URL := http://wiki.openpilot.org/download/attachments/18612236/gtest-1.6.0 # When changing PYTHON_DIR, you must also update it in ground/openpilotgcs/src/python.pri # When changing SDL_DIR or OPENSSL_DIR, you must also update them in ground/openpilotgcs/openpilotgcs.pri ARM_SDK_DIR := $(TOOLS_DIR)/gcc-arm-none-eabi-4_8-2014q1 -QT_SDK_DIR := $(TOOLS_DIR)/qt-5.3.1 +QT_SDK_DIR := $(TOOLS_DIR)/qt-5.3.2 MINGW_DIR := $(QT_SDK_DIR)/Tools/mingw48_32 PYTHON_DIR := $(QT_SDK_DIR)/Tools/mingw48_32/opt/bin NSIS_DIR := $(TOOLS_DIR)/nsis-2.46-unicode @@ -506,12 +506,12 @@ qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR) # Extract packages under tool directory $(V1) $(MKDIR) -p $$(call toprel, $(dir $(2))) $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0qt-project-url.7z" | grep -v Extracting - $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/5.3.1ThirdPartySoftware_Listing.7z" | grep -v Extracting + $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/5.3.2ThirdPartySoftware_Listing.7z" | grep -v Extracting $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0readme.7z" | grep -v Extracting - $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0qt5_essentials.7z" | grep -v Extracting -# $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6).essentials/5.3.1icu_path_patcher.sh.7z" | grep -v Extracting - $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0qt5_addons.7z" | grep -v Extracting -# go to OpenPilot/tools/5.3.1/gcc_64 and call patcher.sh + $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.2-0qt5_essentials.7z" | grep -v Extracting +# $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6).essentials/5.3.2icu_path_patcher.sh.7z" | grep -v Extracting + $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.2-0qt5_addons.7z" | grep -v Extracting +# go to OpenPilot/tools/5.3.2/gcc_64 and call patcher.sh @$(ECHO) @$(ECHO) "Running patcher in" $$(call toprel, $(QT_SDK_PREFIX)) $(V1) $(CD) $(QT_SDK_PREFIX) From d99aba54e33638a17cb2cb40a44e7c7f15ec1c6f Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Wed, 17 Sep 2014 22:44:08 +0200 Subject: [PATCH 169/203] OP-1222 Added ground shapes : Motorbike, Tank and Car --- .../plugins/config/images/ground-shapes.svg | 2579 +++++++++++++++++ 1 file changed, 2579 insertions(+) create mode 100644 ground/openpilotgcs/src/plugins/config/images/ground-shapes.svg diff --git a/ground/openpilotgcs/src/plugins/config/images/ground-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/ground-shapes.svg new file mode 100644 index 000000000..b01fec06e --- /dev/null +++ b/ground/openpilotgcs/src/plugins/config/images/ground-shapes.svg @@ -0,0 +1,2579 @@ + + + +image/svg+xml \ No newline at end of file From e88b8ccbdb1fec1b85fea3294236c8b2be297035 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Thu, 18 Sep 2014 20:05:44 +0200 Subject: [PATCH 170/203] OP-1222 FW_Wizard Ground shapes : Better labels, cleanup --- .../plugins/config/images/ground-shapes.svg | 2716 ++++++++++------- 1 file changed, 1632 insertions(+), 1084 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/ground-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/ground-shapes.svg index b01fec06e..ee8cd7410 100644 --- a/ground/openpilotgcs/src/plugins/config/images/ground-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/ground-shapes.svg @@ -20,7 +20,7 @@ enable-background="new 0 0 792 1008" xml:space="preserve" inkscape:version="0.48.5 r10040" - sodipodi:docname="ground-shapes-wizard.svg" + sodipodi:docname="ground-shapes.svg.2014_09_18_19_55_33.0.svg" inkscape:export-filename="/home/laurent/Images/car.png" inkscape:export-xdpi="70.479134" inkscape:export-ydpi="70.479134"> \ No newline at end of file + d="M 164.97807,1032.3266 C 132.36283,1032.3266 105.93071,1058.7587 105.93071,1091.374 C 105.93071,1123.9892 132.36283,1150.4214 164.97807,1150.4214 L 523.74691,1150.8947 C 556.36217,1150.8947 582.79428,1124.4627 582.79428,1091.8473 C 582.79428,1059.2321 556.36217,1032.7999 523.74691,1032.7999 L 164.97807,1032.3266 z M 165.12756,1038.5054 L 523.59742,1038.9289 C 552.80971,1038.9289 576.49091,1062.6101 576.49091,1091.8224 C 576.49091,1121.0348 552.80971,1144.7159 523.59742,1144.7159 L 165.12756,1144.2924 C 135.91528,1144.2924 112.23408,1120.6112 112.23408,1091.3989 C 112.23408,1062.1866 135.91528,1038.5054 165.12756,1038.5054 z" + style="opacity:0.95864659;color:#000000;fill:#4e93f6;fill-opacity:1;fill-rule:nonzero;stroke:#131715;stroke-width:0.36675274;stroke-linecap:butt;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;stroke-dashoffset:0;marker:none;visibility:visible;display:inline;overflow:visible;enable-background:accumulate" /> \ No newline at end of file From a5ebf36425de260a8d709de86f3e7f0de0fe46eb Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sun, 21 Sep 2014 16:38:52 +0200 Subject: [PATCH 171/203] OP-1499 - Replay the configuration sequence in case of gps disconnection, add retry logic in case of errors --- flight/modules/GPS/GPS.c | 4 ++- flight/modules/GPS/UBX.c | 8 ++++++ flight/modules/GPS/inc/ubx_autoconfig.h | 18 ++++++++---- flight/modules/GPS/ubx_autoconfig.c | 37 ++++++++++++++++++++++--- 4 files changed, 56 insertions(+), 11 deletions(-) diff --git a/flight/modules/GPS/GPS.c b/flight/modules/GPS/GPS.c index 9729c5189..2517aef98 100644 --- a/flight/modules/GPS/GPS.c +++ b/flight/modules/GPS/GPS.c @@ -245,7 +245,9 @@ static void gpsTask(__attribute__((unused)) void *parameters) if (gpsSettings.DataProtocol == GPSSETTINGS_DATAPROTOCOL_UBX) { char *buffer = 0; uint16_t count = 0; - ubx_autoconfig_run(&buffer, &count); + uint8_t status; + GPSPositionSensorStatusGet(&status); + ubx_autoconfig_run(&buffer, &count, status != GPSPOSITIONSENSOR_STATUS_NOGPS); // Something to send? if (count) { PIOS_COM_SendBuffer(gpsPort, (uint8_t *)buffer, count); diff --git a/flight/modules/GPS/UBX.c b/flight/modules/GPS/UBX.c index ba417b5ac..c883e7a39 100644 --- a/flight/modules/GPS/UBX.c +++ b/flight/modules/GPS/UBX.c @@ -515,6 +515,14 @@ uint32_t parse_ubx_message(struct UBXPacket *ubx, GPSPositionSensorData *GpsPosi GPSPositionSensorSet(GpsPosition); msgtracker.msg_received = NONE_RECEIVED; id = GPSPOSITIONSENSOR_OBJID; + } else { + uint8_t status; + GPSPositionSensorStatusGet(&status); + if (status == GPSPOSITIONSENSOR_STATUS_NOGPS) { + // Some ubx thing has been received so GPS is there + status = GPSPOSITIONSENSOR_STATUS_NOFIX; + GPSPositionSensorStatusSet(&status); + } } return id; } diff --git a/flight/modules/GPS/inc/ubx_autoconfig.h b/flight/modules/GPS/inc/ubx_autoconfig.h index e01391a7d..25a5857b0 100644 --- a/flight/modules/GPS/inc/ubx_autoconfig.h +++ b/flight/modules/GPS/inc/ubx_autoconfig.h @@ -33,12 +33,18 @@ // defines // TODO: NEO8 max rate is for Rom version, flash is limited to 10Hz, need to handle that. -#define UBX_MAX_RATE_VER8 18 -#define UBX_MAX_RATE_VER7 10 -#define UBX_MAX_RATE 5 +#define UBX_MAX_RATE_VER8 18 +#define UBX_MAX_RATE_VER7 10 +#define UBX_MAX_RATE 5 -#define UBX_REPLY_TIMEOUT (500 * 1000) -#define UBX_MAX_RETRIES 5 +// time to wait before reinitializing the fsm due to disconnection +#define UBX_CONNECTION_TIMEOUT (2000 * 1000) +// times between retries in case an error does occurs +#define UBX_ERROR_RETRY_TIMEOUT (1000 * 1000) +// timeout for ack reception +#define UBX_REPLY_TIMEOUT (500 * 1000) +// max retries in case of timeout +#define UBX_MAX_RETRIES 5 // types typedef enum { @@ -179,7 +185,7 @@ typedef union { } message; } __attribute__((packed)) UBXSentPacket_t; -void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send); +void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send, bool gps_connected); void ubx_autoconfig_set(ubx_autoconfig_settings_t config); int32_t ubx_autoconfig_get_status(); #endif /* UBX_AUTOCONFIG_H_ */ diff --git a/flight/modules/GPS/ubx_autoconfig.c b/flight/modules/GPS/ubx_autoconfig.c index 74aa89179..fbecfa9f7 100644 --- a/flight/modules/GPS/ubx_autoconfig.c +++ b/flight/modules/GPS/ubx_autoconfig.c @@ -46,6 +46,7 @@ typedef enum { typedef struct { initSteps_t currentStep; // Current configuration "fsm" status uint32_t lastStepTimestampRaw; // timestamp of last operation + uint32_t lastConnectedRaw; // timestamp of last time gps was connected UBXSentPacket_t working_packet; // outbound "buffer" ubx_autoconfig_settings_t currentSettings; int8_t lastConfigSent; // index of last configuration string sent @@ -279,15 +280,38 @@ static void enable_sentences(__attribute__((unused)) uint16_t *bytes_to_send) } } -void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send) +void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send, bool gps_connected) { *bytes_to_send = 0; *buffer = (char *)status->working_packet.buffer; - if (!status || !enabled) { + if (!status || !enabled || status->currentStep == INIT_STEP_DISABLED) { return; // autoconfig not enabled } + + // when gps is disconnected it will replay the autoconfig sequence. + if (!gps_connected) { + if (status->currentStep == INIT_STEP_DONE) { + // if some operation is in progress and it is not running into issues it maybe that + // the disconnection is only due to wrong message rates, so reinit only when done. + // errors caused by disconnection are handled by error retry logic + if (PIOS_DELAY_DiffuS(status->lastConnectedRaw) > UBX_CONNECTION_TIMEOUT) { + status->currentStep = INIT_STEP_START; + return; + } + } + } else { + // reset connection timer + status->lastConnectedRaw = PIOS_DELAY_GetRaw(); + } + switch (status->currentStep) { - case INIT_STEP_ERROR: // TODO: what to do? retries after a while? maybe gps was disconnected (this can be detected)? + case INIT_STEP_ERROR: + if (PIOS_DELAY_DiffuS(status->lastStepTimestampRaw) > UBX_ERROR_RETRY_TIMEOUT) { + status->currentStep = INIT_STEP_START; + status->lastStepTimestampRaw = PIOS_DELAY_GetRaw(); + } + return; + case INIT_STEP_DISABLED: case INIT_STEP_DONE: return; @@ -348,6 +372,7 @@ void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send) status->retryCount++; if (status->retryCount > UBX_MAX_RETRIES) { status->currentStep = INIT_STEP_ERROR; + status->lastStepTimestampRaw = PIOS_DELAY_GetRaw(); return; } } @@ -374,12 +399,16 @@ void ubx_autoconfig_set(ubx_autoconfig_settings_t config) status->currentSettings = config; status->currentStep = INIT_STEP_START; enabled = true; + } else { + if (!status) { + status->currentStep = INIT_STEP_DISABLED; + } } } int32_t ubx_autoconfig_get_status() { - if (!status) { + if (!status || !enabled) { return UBX_AUTOCONFIG_STATUS_DISABLED; } switch (status->currentStep) { From cc381075ceb54837ae6df72e14cb59c17f0c05e7 Mon Sep 17 00:00:00 2001 From: m_thread Date: Sun, 21 Sep 2014 22:59:56 +0200 Subject: [PATCH 172/203] OP-1222 We don't add personal names to the @author tag --- .../plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index ff9c3e8c3..42118be0b 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -2,7 +2,7 @@ ****************************************************************************** * * @file configfixedwingwidget.cpp - * @author E. Lafargue & The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. + * @author The OpenPilot Team, http://www.openpilot.org Copyright (C) 2012. * @addtogroup GCSPlugins GCS Plugins * @{ * @addtogroup ConfigPlugin Config Plugin From 3c6a8e03958e8f7dc27900072b76356488e00eac Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sun, 21 Sep 2014 23:32:52 +0200 Subject: [PATCH 173/203] OP-1379 - Prevent loosing any update to background notification and notifications with priority higher than current --- flight/pios/common/pios_notify.c | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/flight/pios/common/pios_notify.c b/flight/pios/common/pios_notify.c index 5f47a18a6..9b0a1fc67 100644 --- a/flight/pios/common/pios_notify.c +++ b/flight/pios/common/pios_notify.c @@ -58,6 +58,13 @@ pios_notify_notification PIOS_NOTIFY_GetActiveNotification(bool clear) */ void PIOS_NOTIFICATION_Default_Ext_Led_Play(const LedSequence_t *sequence, pios_notify_priority priority) { + // alert and alarms are repeated if condition persists. bacground notification instead are set once, so try to prevent loosing any update + if (newNotification && priority != NOTIFY_PRIORITY_BACKGROUND) { + // prevent overwriting higher priority or background notifications + if (extLedNotification.priority == NOTIFY_PRIORITY_BACKGROUND || extLedNotification.priority > priority) { + return; + } + } extLedNotification.priority = priority; extLedNotification.sequence = *sequence; newNotification = true; From 0885fda9263a8c1da60c73c4d378d9643051cc8c Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Mon, 22 Sep 2014 00:56:49 +0200 Subject: [PATCH 174/203] OP-1499 - CFG-CFG mask was incorrect (nav is 0x02, not 0x01) --- flight/modules/GPS/ubx_autoconfig.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/flight/modules/GPS/ubx_autoconfig.c b/flight/modules/GPS/ubx_autoconfig.c index fbecfa9f7..bf9b41cf7 100644 --- a/flight/modules/GPS/ubx_autoconfig.c +++ b/flight/modules/GPS/ubx_autoconfig.c @@ -228,7 +228,7 @@ void config_save(uint16_t *bytes_to_send) { memset(status->working_packet.buffer, 0, sizeof(UBXSentHeader_t) + sizeof(ubx_cfg_cfg_t)); // mask LSB=ioPort|msgConf|infMsg|navConf|rxmConf|||||rinvConf|antConf|....|= MSB - status->working_packet.message.payload.cfg_cfg.saveMask = 0x01 | 0x08; // msgConf + navConf + status->working_packet.message.payload.cfg_cfg.saveMask = 0x02 | 0x08; // msgConf + navConf status->working_packet.message.payload.cfg_cfg.deviceMask = UBX_CFG_CFG_ALL_DEVICES_MASK; *bytes_to_send = prepare_packet(&status->working_packet, UBX_CLASS_CFG, UBX_ID_CFG_CFG, sizeof(ubx_cfg_cfg_t)); status->requiredAck.clsID = UBX_CLASS_CFG; From 0d6aabe37bea2c0312c62920a17cab89f67d6088 Mon Sep 17 00:00:00 2001 From: m_thread Date: Wed, 24 Sep 2014 01:06:16 +0200 Subject: [PATCH 175/203] OP-1222 Added generated file name and export to a specific directory. Added scaling of image to save file size. Added sanity check of input data to not be empty fields. --- .../cfg_vehicletypes/configfixedwingwidget.h | 2 - .../vehicletemplateexportdialog.cpp | 122 ++++++++++++------ .../setupwizard/vehicletemplateexportdialog.h | 6 +- .../vehicletemplateexportdialog.ui | 100 ++++++++++---- 4 files changed, 161 insertions(+), 69 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index 5e25d99d3..7f9ad7891 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -65,8 +65,6 @@ private: protected: void enableControls(bool enable); - void resizeEvent(QResizeEvent *); - void showEvent(QShowEvent *); private slots: virtual void setupUI(QString airframeType); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp index 9e94aea2e..73d9853c6 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp @@ -34,6 +34,9 @@ #include #include #include +#include +#include +#include #include "stabilizationsettings.h" #include "stabilizationsettingsbank1.h" #include "stabilizationsettingsbank2.h" @@ -50,6 +53,12 @@ VehicleTemplateExportDialog::VehicleTemplateExportDialog(QWidget *parent) : m_uavoManager = pm->getObject(); ui->Photo->setScene(new QGraphicsScene(this)); ui->Type->setText(setupVehicleType()); + + connect(ui->Name, SIGNAL(textChanged(QString)), this, SLOT(updateStatus())); + connect(ui->Owner, SIGNAL(textChanged(QString)), this, SLOT(updateStatus())); + connect(ui->ForumNick, SIGNAL(textChanged(QString)), this, SLOT(updateStatus())); + connect(ui->Size, SIGNAL(textChanged(QString)), this, SLOT(updateStatus())); + connect(ui->Weight, SIGNAL(textChanged(QString)), this, SLOT(updateStatus())); } VehicleTemplateExportDialog::~VehicleTemplateExportDialog() @@ -146,52 +155,65 @@ QString VehicleTemplateExportDialog::setupVehicleType() } } +QString VehicleTemplateExportDialog::fixFilenameString(QString input, int truncate) +{ + return input.replace(' ', "").replace('|', "").replace('/', "") + .replace('\\', "").replace(':', "").replace('"', "") + .replace('\'', "").replace('?', "").replace('*', "") + .replace('>', "").replace('<', "") + .replace('}', "").replace('{', "") + .left(truncate); +} + void VehicleTemplateExportDialog::accept() { - QString fileName = QFileDialog::getSaveFileName(this, tr("Export template"), "", tr("Template (*.optmpl)")); + QJsonObject exportObject; - if (!fileName.isEmpty()) { - if (!fileName.endsWith(".optmpl")) { - fileName += ".optmpl"; - } - QFile saveFile(fileName); - if (saveFile.open(QIODevice::WriteOnly)) { - QJsonObject exportObject; + QList objectsToExport; + objectsToExport << StabilizationSettings::GetInstance(m_uavoManager); + objectsToExport << StabilizationSettingsBank1::GetInstance(m_uavoManager); + objectsToExport << StabilizationSettingsBank2::GetInstance(m_uavoManager); + objectsToExport << StabilizationSettingsBank3::GetInstance(m_uavoManager); + objectsToExport << EKFConfiguration::GetInstance(m_uavoManager); + m_uavoManager->toJson(exportObject, objectsToExport); - QList objectsToExport; - objectsToExport << StabilizationSettings::GetInstance(m_uavoManager); - objectsToExport << StabilizationSettingsBank1::GetInstance(m_uavoManager); - objectsToExport << StabilizationSettingsBank2::GetInstance(m_uavoManager); - objectsToExport << StabilizationSettingsBank3::GetInstance(m_uavoManager); - objectsToExport << EKFConfiguration::GetInstance(m_uavoManager); - m_uavoManager->toJson(exportObject, objectsToExport); + exportObject["type"] = m_type; + exportObject["subtype"] = m_subType; + exportObject["name"] = ui->Name->text(); + exportObject["owner"] = ui->Owner->text(); + exportObject["nick"] = ui->ForumNick->text(); + exportObject["size"] = ui->Size->text(); + exportObject["weight"] = ui->Weight->text(); + exportObject["motor"] = ui->Motor->text(); + exportObject["esc"] = ui->Esc->text(); + exportObject["servo"] = ui->Servo->text(); + exportObject["battery"] = ui->Battery->text(); + exportObject["propeller"] = ui->Propeller->text(); + exportObject["controller"] = ui->Controllers->currentText(); + exportObject["comment"] = ui->Comment->document()->toPlainText(); - exportObject["type"] = m_type; - exportObject["subtype"] = m_subType; - exportObject["name"] = ui->Name->text(); - exportObject["owner"] = ui->Owner->text(); - exportObject["nick"] = ui->ForumNick->text(); - exportObject["size"] = ui->Size->text(); - exportObject["weight"] = ui->Weight->text(); - exportObject["motor"] = ui->Motor->text(); - exportObject["esc"] = ui->Esc->text(); - exportObject["servo"] = ui->Servo->text(); - exportObject["battery"] = ui->Battery->text(); - exportObject["propeller"] = ui->Propeller->text(); - exportObject["controller"] = ui->Controllers->currentText(); - exportObject["comment"] = ui->Comment->document()->toPlainText(); + QByteArray bytes; + QBuffer buffer(&bytes); + buffer.open(QIODevice::WriteOnly); + m_image.scaled(500, 500, Qt::KeepAspectRatio).save(&buffer, "PNG"); + exportObject["photo"] = bytes.toBase64().data(); - QByteArray bytes; - QBuffer buffer(&bytes); - buffer.open(QIODevice::WriteOnly); - m_image.save(&buffer, "PNG"); - exportObject["photo"] = bytes.toBase64().data(); + QJsonDocument saveDoc(exportObject); - QJsonDocument saveDoc(exportObject); - saveFile.write(saveDoc.toJson()); - saveFile.close(); - } + QString fileName = QString("../share/openpilotgcs/cloudconfig/%1/%2-%3-%4-%5.optmpl") + .arg(getTypeDirectory()) + .arg(fixFilenameString(ui->ForumNick->text(), 15)) + .arg(fixFilenameString(ui->Name->text(), 20)) + .arg(fixFilenameString(ui->Type->text(), 30)) + .arg(fixFilenameString(QUuid::createUuid().toString().right(12))); + QFile saveFile(fileName); + QDir dir; + dir.mkpath(QFileInfo(saveFile).absoluteDir().absolutePath()); + if (saveFile.open(QIODevice::WriteOnly)) { + saveFile.write(saveDoc.toJson()); + saveFile.close(); + QMessageBox::information(this, "Export", tr("Settings were exported to \n%1").arg(QFileInfo(saveFile).absoluteFilePath()),QMessageBox::Ok); } QDialog::accept(); } @@ -207,3 +229,27 @@ void VehicleTemplateExportDialog::importImage() ui->Photo->fitInView(ui->Photo->scene()->itemsBoundingRect(), Qt::KeepAspectRatio); } } + +QString VehicleTemplateExportDialog::getTypeDirectory() +{ + switch(m_type) { + case VehicleConfigurationSource::VEHICLE_FIXEDWING: + return "fixedwing"; + case VehicleConfigurationSource::VEHICLE_MULTI: + return "multirotor"; + case VehicleConfigurationSource::VEHICLE_HELI: + return "helicopter"; + case VehicleConfigurationSource::VEHICLE_SURFACE: + return "surface"; + default: + return "custom"; + } +} + +void VehicleTemplateExportDialog::updateStatus() +{ + ui->acceptBtn->setEnabled(ui->Name->text().length() > 3 && ui->Owner->text().length() > 2 && + ui->ForumNick->text().length() > 2 && ui->Size->text().length() > 0 && + ui->Weight->text().length() > 0); + +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h index 99af7751b..c310d7754 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h @@ -45,6 +45,7 @@ public: public slots: void accept(); + void updateStatus(); private slots: void importImage(); @@ -52,10 +53,13 @@ private slots: private: Ui::VehicleTemplateExportDialog *ui; UAVObjectManager *m_uavoManager; - QString setupVehicleType(); VehicleConfigurationSource::VEHICLE_TYPE m_type; VehicleConfigurationSource::VEHICLE_SUB_TYPE m_subType; QPixmap m_image; + + QString getTypeDirectory(); + QString setupVehicleType(); + QString fixFilenameString(QString input, int truncate = 100); }; #endif // VEHICLETEMPLATEEXPORTDIALOG_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui index 2a1fd7613..f03f7a33c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui @@ -413,14 +413,58 @@ - - - - Qt::Horizontal + + + + QFrame::NoFrame - - QDialogButtonBox::Cancel|QDialogButtonBox::Save + + QFrame::Raised + + + 0 + + + 0 + + + 0 + + + 0 + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + Cancel + + + + + + + false + + + Ok + + + + @@ -428,34 +472,34 @@ - buttonBox - accepted() - VehicleTemplateExportDialog - accept() - - - 248 - 254 - - - 157 - 274 - - - - - buttonBox - rejected() + cancelBtn + clicked() VehicleTemplateExportDialog reject() - 316 - 260 + 458 + 668 - 286 - 274 + 304 + 349 + + + + + acceptBtn + clicked() + VehicleTemplateExportDialog + accept() + + + 549 + 668 + + + 304 + 349 From 78756f6873a8e40debb6d09d5baf39c58340b77f Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Wed, 24 Sep 2014 06:12:48 +0200 Subject: [PATCH 176/203] OP-1499 - Failed Autoconfig will raise an Error Alarm. When AC does start it will reset any previous ack. Force update to Autoconfig Status in GPSPositionSensor UAVO. Add a small pause between each config step --- flight/modules/GPS/GPS.c | 9 ++++++++- flight/modules/GPS/inc/ubx_autoconfig.h | 3 ++- flight/modules/GPS/ubx_autoconfig.c | 8 +++++++- 3 files changed, 17 insertions(+), 3 deletions(-) diff --git a/flight/modules/GPS/GPS.c b/flight/modules/GPS/GPS.c index 2517aef98..e8524fd2e 100644 --- a/flight/modules/GPS/GPS.c +++ b/flight/modules/GPS/GPS.c @@ -268,11 +268,17 @@ static void gpsTask(__attribute__((unused)) void *parameters) { #if defined(PIOS_INCLUDE_GPS_UBX_PARSER) && !defined(PIOS_GPS_MINIMAL) int32_t ac_status = ubx_autoconfig_get_status(); + static uint8_t lastStatus = 0; + gpspositionsensor.AutoConfigStatus = ac_status == UBX_AUTOCONFIG_STATUS_DISABLED ? GPSPOSITIONSENSOR_AUTOCONFIGSTATUS_DISABLED : ac_status == UBX_AUTOCONFIG_STATUS_DONE ? GPSPOSITIONSENSOR_AUTOCONFIGSTATUS_DONE : ac_status == UBX_AUTOCONFIG_STATUS_ERROR ? GPSPOSITIONSENSOR_AUTOCONFIGSTATUS_ERROR : GPSPOSITIONSENSOR_AUTOCONFIGSTATUS_RUNNING; + if (gpspositionsensor.AutoConfigStatus != lastStatus) { + GPSPositionSensorAutoConfigStatusSet(&gpspositionsensor.AutoConfigStatus); + lastStatus = gpspositionsensor.AutoConfigStatus; + } #endif res = parse_ubx_stream(c, gps_rx_buffer, &gpspositionsensor, &gpsRxStats); } @@ -292,7 +298,8 @@ static void gpsTask(__attribute__((unused)) void *parameters) // Check for GPS timeout timeNowMs = xTaskGetTickCount() * portTICK_RATE_MS; - if ((timeNowMs - timeOfLastUpdateMs) >= GPS_TIMEOUT_MS) { + if ((timeNowMs - timeOfLastUpdateMs) >= GPS_TIMEOUT_MS || + (gpsSettings.DataProtocol == GPSSETTINGS_DATAPROTOCOL_UBX && gpspositionsensor.AutoConfigStatus == GPSPOSITIONSENSOR_AUTOCONFIGSTATUS_ERROR)) { // we have not received any valid GPS sentences for a while. // either the GPS is not plugged in or a hardware problem or the GPS has locked up. uint8_t status = GPSPOSITIONSENSOR_STATUS_NOGPS; diff --git a/flight/modules/GPS/inc/ubx_autoconfig.h b/flight/modules/GPS/inc/ubx_autoconfig.h index 25a5857b0..734c54537 100644 --- a/flight/modules/GPS/inc/ubx_autoconfig.h +++ b/flight/modules/GPS/inc/ubx_autoconfig.h @@ -45,7 +45,8 @@ #define UBX_REPLY_TIMEOUT (500 * 1000) // max retries in case of timeout #define UBX_MAX_RETRIES 5 - +// pause between each configuration step +#define UBX_STEP_WAIT_TIME (10 * 1000) // types typedef enum { UBX_AUTOCONFIG_STATUS_DISABLED = 0, diff --git a/flight/modules/GPS/ubx_autoconfig.c b/flight/modules/GPS/ubx_autoconfig.c index bf9b41cf7..1671b601a 100644 --- a/flight/modules/GPS/ubx_autoconfig.c +++ b/flight/modules/GPS/ubx_autoconfig.c @@ -287,7 +287,9 @@ void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send, bool gps_connec if (!status || !enabled || status->currentStep == INIT_STEP_DISABLED) { return; // autoconfig not enabled } - + if (PIOS_DELAY_DiffuS(status->lastStepTimestampRaw) < UBX_STEP_WAIT_TIME) { + return; + } // when gps is disconnected it will replay the autoconfig sequence. if (!gps_connected) { if (status->currentStep == INIT_STEP_DONE) { @@ -318,6 +320,10 @@ void ubx_autoconfig_run(char * *buffer, uint16_t *bytes_to_send, bool gps_connec case INIT_STEP_START: case INIT_STEP_ASK_VER: + // clear ack + ubxLastAck.clsID = 0x00; + ubxLastAck.msgID = 0x00; + status->lastStepTimestampRaw = PIOS_DELAY_GetRaw(); build_request(&status->working_packet, UBX_CLASS_MON, UBX_ID_MON_VER, bytes_to_send); status->currentStep = INIT_STEP_WAIT_VER; From 9c0c489e941efb7fb38152fefc249ee7be40be35 Mon Sep 17 00:00:00 2001 From: m_thread Date: Wed, 24 Sep 2014 08:26:31 +0200 Subject: [PATCH 177/203] OP-1222 Added some constants instead of hard coded values. --- .../vehicletemplateexportdialog.cpp | 25 +++++++++++++------ .../setupwizard/vehicletemplateexportdialog.h | 9 +++++++ 2 files changed, 27 insertions(+), 7 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp index 73d9853c6..face12779 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp @@ -43,6 +43,13 @@ #include "stabilizationsettingsbank3.h" #include "ekfconfiguration.h" +const char* VehicleTemplateExportDialog::EXPORT_BASE_NAME = "../share/openpilotgcs/cloudconfig"; +const char* VehicleTemplateExportDialog::EXPORT_FIXEDWING_NAME = "fixedwing"; +const char* VehicleTemplateExportDialog::EXPORT_MULTI_NAME = "multirotor"; +const char* VehicleTemplateExportDialog::EXPORT_HELI_NAME = "helicopter"; +const char* VehicleTemplateExportDialog::EXPORT_SURFACE_NAME = "surface"; +const char* VehicleTemplateExportDialog::EXPORT_CUSTOM_NAME = "custom"; + VehicleTemplateExportDialog::VehicleTemplateExportDialog(QWidget *parent) : QDialog(parent), ui(new Ui::VehicleTemplateExportDialog) @@ -196,12 +203,13 @@ void VehicleTemplateExportDialog::accept() QByteArray bytes; QBuffer buffer(&bytes); buffer.open(QIODevice::WriteOnly); - m_image.scaled(500, 500, Qt::KeepAspectRatio).save(&buffer, "PNG"); + m_image.scaled(IMAGE_SCALE_WIDTH, IMAGE_SCALE_HEIGHT, Qt::KeepAspectRatio).save(&buffer, "PNG"); exportObject["photo"] = bytes.toBase64().data(); QJsonDocument saveDoc(exportObject); - QString fileName = QString("../share/openpilotgcs/cloudconfig/%1/%2-%3-%4-%5.optmpl") + QString fileName = QString("%1/%2/%3-%4-%5-%6.optmpl") + .arg(EXPORT_BASE_NAME) .arg(getTypeDirectory()) .arg(fixFilenameString(ui->ForumNick->text(), 15)) .arg(fixFilenameString(ui->Name->text(), 20)) @@ -214,6 +222,9 @@ void VehicleTemplateExportDialog::accept() saveFile.write(saveDoc.toJson()); saveFile.close(); QMessageBox::information(this, "Export", tr("Settings were exported to \n%1").arg(QFileInfo(saveFile).absoluteFilePath()),QMessageBox::Ok); + } else { + QMessageBox::information(this, "Export", tr("Settings could not be exported to \n%1.\nPlease try again.") + .arg(QFileInfo(saveFile).absoluteFilePath()),QMessageBox::Ok); } QDialog::accept(); } @@ -234,15 +245,15 @@ QString VehicleTemplateExportDialog::getTypeDirectory() { switch(m_type) { case VehicleConfigurationSource::VEHICLE_FIXEDWING: - return "fixedwing"; + return EXPORT_FIXEDWING_NAME; case VehicleConfigurationSource::VEHICLE_MULTI: - return "multirotor"; + return EXPORT_MULTI_NAME; case VehicleConfigurationSource::VEHICLE_HELI: - return "helicopter"; + return EXPORT_HELI_NAME; case VehicleConfigurationSource::VEHICLE_SURFACE: - return "surface"; + return EXPORT_SURFACE_NAME; default: - return "custom"; + return EXPORT_CUSTOM_NAME; } } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h index c310d7754..2e1d3a772 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h @@ -40,6 +40,13 @@ class VehicleTemplateExportDialog : public QDialog { Q_OBJECT public: + static const char* EXPORT_BASE_NAME; + static const char* EXPORT_FIXEDWING_NAME; + static const char* EXPORT_MULTI_NAME; + static const char* EXPORT_HELI_NAME; + static const char* EXPORT_SURFACE_NAME; + static const char* EXPORT_CUSTOM_NAME; + explicit VehicleTemplateExportDialog(QWidget *parent = 0); ~VehicleTemplateExportDialog(); @@ -51,6 +58,8 @@ private slots: void importImage(); private: + static const int IMAGE_SCALE_WIDTH = 500; + static const int IMAGE_SCALE_HEIGHT = 500; Ui::VehicleTemplateExportDialog *ui; UAVObjectManager *m_uavoManager; VehicleConfigurationSource::VEHICLE_TYPE m_type; From 7ab2839b6e4f84c412c42acf040ed71750a34c89 Mon Sep 17 00:00:00 2001 From: m_thread Date: Wed, 24 Sep 2014 15:48:28 +0200 Subject: [PATCH 178/203] OP-1222 Implemented scanning for and reading of optmpl files (json vehicle template files ) and implemented selection gui for the templates. --- .../pages/airframeinitialtuningpage.cpp | 170 ++++++++++++- .../pages/airframeinitialtuningpage.h | 22 ++ .../pages/airframeinitialtuningpage.ui | 144 ++++++----- .../src/plugins/setupwizard/setupwizard.cpp | 17 +- .../src/plugins/setupwizard/setupwizard.h | 12 + .../setupwizard/vehicleconfigurationsource.h | 4 +- .../vehicletemplateexportdialog.cpp | 54 ++-- .../setupwizard/vehicletemplateexportdialog.h | 14 +- .../vehicletemplateexportdialog.ui | 233 ++++++++++++------ 9 files changed, 486 insertions(+), 184 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp index 9983abf76..bae342554 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp @@ -27,15 +27,183 @@ #include "airframeinitialtuningpage.h" #include "ui_airframeinitialtuningpage.h" +#include +#include +#include +#include "vehicletemplateexportdialog.h" AirframeInitialTuningPage::AirframeInitialTuningPage(SetupWizard *wizard, QWidget *parent) : AbstractWizardPage(wizard, parent), - ui(new Ui::AirframeInitialTuningPage) + ui(new Ui::AirframeInitialTuningPage), m_dir(NULL), m_photoItem(NULL) { ui->setupUi(this); + ui->templateImage->setScene(new QGraphicsScene()); + connect(ui->templateList, SIGNAL(itemSelectionChanged()), this, SLOT(templateSelectionChanged())); } AirframeInitialTuningPage::~AirframeInitialTuningPage() { + ui->templateList->clear(); + foreach(QJsonObject * templ, m_templates.values()) { + delete templ; + } + m_templates.clear(); + delete ui; } + +void AirframeInitialTuningPage::initializePage() +{ + switch (getWizard()->getVehicleType()) { + case VehicleConfigurationSource::VEHICLE_FIXEDWING: + m_dir = VehicleTemplateExportDialog::EXPORT_FIXEDWING_NAME; + break; + case VehicleConfigurationSource::VEHICLE_MULTI: + m_dir = VehicleTemplateExportDialog::EXPORT_MULTI_NAME; + break; + case VehicleConfigurationSource::VEHICLE_HELI: + m_dir = VehicleTemplateExportDialog::EXPORT_HELI_NAME; + break; + case VehicleConfigurationSource::VEHICLE_SURFACE: + m_dir = VehicleTemplateExportDialog::EXPORT_SURFACE_NAME; + break; + default: + m_dir = NULL; + break; + } + loadValidFiles(); + setupTemplateList(); +} + +bool AirframeInitialTuningPage::validatePage() +{ + QJsonObject *templ = NULL; + + if (ui->templateList->currentRow() >= 0) { + templ = ui->templateList->item(ui->templateList->currentRow())->data(Qt::UserRole + 1).value(); + } + getWizard()->setVehicleTemplate(new QJsonObject(*templ)); + return true; +} + +bool AirframeInitialTuningPage::isComplete() const +{ + return true; +} + +void AirframeInitialTuningPage::updatePhoto(QJsonObject *templ) +{ + QPixmap photo; + + if (m_photoItem != NULL) { + ui->templateImage->scene()->removeItem(m_photoItem); + } + if (templ != NULL) { + QByteArray imageData = QByteArray::fromBase64(templ->value("photo").toString().toLatin1()); + photo.loadFromData(imageData, "PNG"); + } else { + photo.load(":/core/images/opie_90x120.gif"); + } + m_photoItem = ui->templateImage->scene()->addPixmap(photo); + ui->templateImage->setSceneRect(ui->templateImage->scene()->itemsBoundingRect()); + ui->templateImage->fitInView(ui->templateImage->scene()->itemsBoundingRect(), Qt::KeepAspectRatio); +} + +void AirframeInitialTuningPage::updateDescription(QJsonObject *templ) +{ + if (templ != NULL) { + QString description; + description.append("").append(tr("Name of Vehicle: ")).append("").append(templ->value("name").toString()).append("
"); + description.append("").append(tr("Name of Owner: ")).append("").append(templ->value("owner").toString()) + .append(" (").append(templ->value("nick").toString()).append(")").append("
"); + description.append("").append(tr("Size: ")).append("").append(templ->value("size").toString()).append("
"); + description.append("").append(tr("Weight: ")).append("").append(templ->value("weight").toString()).append("
"); + description.append("").append(tr("Motor(s): ")).append("").append(templ->value("motor").toString()).append("
"); + description.append("").append(tr("ESC(s): ")).append("").append(templ->value("esc").toString()).append("
"); + description.append("").append(tr("Servo(s): ")).append("").append(templ->value("servo").toString()).append("
"); + description.append("").append(tr("Battery: ")).append("").append(templ->value("battery").toString()).append("
"); + description.append("").append(tr("Propellers(s): ")).append("").append(templ->value("propeller").toString()).append("
"); + description.append("").append(tr("Controller: ")).append("").append(templ->value("controller").toString()).append("
"); + description.append("").append(tr("Comments: ")).append("").append(templ->value("comment").toString()); + ui->templateDescription->setText(description); + } else { + ui->templateDescription->setText(tr("No vehicle selected!")); + } +} + +void AirframeInitialTuningPage::templateSelectionChanged() +{ + if (ui->templateList->currentRow() >= 0) { + QJsonObject *templ = ui->templateList->item(ui->templateList->currentRow())->data(Qt::UserRole + 1).value(); + updatePhoto(templ); + updateDescription(templ); + } +} + +void AirframeInitialTuningPage::loadValidFiles() +{ + ui->templateList->clear(); + foreach(QJsonObject * templ, m_templates.values()) { + delete templ; + } + m_templates.clear(); + + QDir templateDir(QString("%1/%2/").arg(VehicleTemplateExportDialog::EXPORT_BASE_NAME).arg(m_dir)); + QStringList names; + names << "*.optmpl"; + templateDir.setNameFilters(names); + templateDir.setSorting(QDir::Name); + QStringList files = templateDir.entryList(); + foreach(QString fileName, files) { + QFile file(QString("%1/%2").arg(templateDir.absolutePath()).arg(fileName)); + + if (file.open(QFile::ReadOnly)) { + QByteArray jsonData = file.readAll(); + QJsonDocument templateDoc = QJsonDocument::fromJson(jsonData); + QJsonObject json = templateDoc.object(); + if (json["type"].toInt() == getWizard()->getVehicleType() && + json["subtype"].toInt() == getWizard()->getVehicleSubType()) { + QString nameKey = getTemplateKey(&json); + int index = 0; + while (true) { + if (!m_templates.contains(nameKey)) { + m_templates[nameKey] = new QJsonObject(json); + break; + } else { + nameKey = QString("%1 - %2").arg(nameKey).arg(++index); + } + } + } + file.close(); + } + } +} + +void AirframeInitialTuningPage::setupTemplateList() +{ + QListWidgetItem *item = new QListWidgetItem(tr("None"), ui->templateList); + + item->setData(Qt::UserRole + 1, QVariant::fromValue((QJsonObject *)NULL)); + foreach(QString templ, m_templates.keys()) { + item = new QListWidgetItem(templ, ui->templateList); + item->setData(Qt::UserRole + 1, QVariant::fromValue(m_templates[templ])); + } + ui->templateList->setCurrentRow(0); +} + +QString AirframeInitialTuningPage::getTemplateKey(QJsonObject *templ) +{ + return QString("%1 - %2").arg(templ->value("nick").toString()).arg(templ->value("name").toString()); +} + +void AirframeInitialTuningPage::resizeEvent(QResizeEvent *) +{ + ui->templateImage->setSceneRect(ui->templateImage->scene()->itemsBoundingRect()); + ui->templateImage->fitInView(ui->templateImage->scene()->itemsBoundingRect(), Qt::KeepAspectRatio); +} + +void AirframeInitialTuningPage::showEvent(QShowEvent *) +{ + ui->templateImage->setSceneRect(ui->templateImage->scene()->itemsBoundingRect()); + ui->templateImage->fitInView(ui->templateImage->scene()->itemsBoundingRect(), Qt::KeepAspectRatio); +} diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.h index fe92e1ee6..d290a8843 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.h @@ -29,6 +29,7 @@ #define AIRFRAMEINITIALTUNINGPAGE_H #include "abstractwizardpage.h" +#include namespace Ui { class AirframeInitialTuningPage; @@ -40,9 +41,30 @@ class AirframeInitialTuningPage : public AbstractWizardPage { public: explicit AirframeInitialTuningPage(SetupWizard *wizard, QWidget *parent = 0); ~AirframeInitialTuningPage(); + void initializePage(); + bool validatePage(); + bool isComplete() const; + +public slots: + void templateSelectionChanged(); + +protected: + void resizeEvent(QResizeEvent *); + void showEvent(QShowEvent *); private: Ui::AirframeInitialTuningPage *ui; + const char *m_dir; + QMap m_templates; + QGraphicsPixmapItem *m_photoItem; + + void loadValidFiles(); + void setupTemplateList(); + QString getTemplateKey(QJsonObject *templ); + void updatePhoto(QJsonObject *templ); + void updateDescription(QJsonObject *templ); }; +Q_DECLARE_METATYPE(QJsonObject *) + #endif // AIRFRAMEINITIALTUNINGPAGE_H diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.ui index 6a87e690a..490cada2b 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.ui @@ -7,80 +7,98 @@ 0 0 600 - 400 + 598
WizardPage - - - - 9 - 9 - 582 - 81 - - - - <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0//EN" "http://www.w3.org/TR/REC-html40/strict.dtd"> + + + + + <!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:12pt; font-weight:600;">Initial Tuning</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-family:'MS Shell Dlg 2,sans-serif';">This section of the OpenPilot Wizard allows you to select a set of initial tunning parameters for your airframe. Presented below is a list of common airframe types, select the one that matches your airframe the closest, if unsure select the generic variant.</span> </p></body></html> - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - true - - - - - - 10 - 100 - 581 - 291 - - - - - - - - - Qt::ScrollBarAlwaysOn - - - - - - - - - - - - Description - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop - - - - - - - - - - label_main - label_main - horizontalLayoutWidget + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop + + + true + + +
+ + + + + + + + + + Qt::ScrollBarAlwaysOn + + + QAbstractItemView::NoEditTriggers + + + + + + + + 250 + 250 + + + + background-color: rgba(254, 254, 254, 0); + + + false + + + QPainter::Antialiasing|QPainter::HighQualityAntialiasing|QPainter::TextAntialiasing + + + + + + + + + + 0 + 0 + + + + + 10 + + + + false + + + true + + + Information about the Vehicle in short. + + + + + + + + diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 7b509be02..f19c6fd51 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -56,8 +56,8 @@ SetupWizard::SetupWizard(QWidget *parent) : QWizard(parent), VehicleConfigurationSource(), m_controllerType(CONTROLLER_UNKNOWN), m_vehicleType(VEHICLE_UNKNOWN), m_inputType(INPUT_UNKNOWN), m_escType(ESC_UNKNOWN), - m_servoType(SERVO_UNKNOWN), m_calibrationPerformed(false), m_restartNeeded(false), - m_connectionManager(0) + m_servoType(SERVO_UNKNOWN), m_vehicleTemplate(NULL), + m_calibrationPerformed(false), m_restartNeeded(false), m_connectionManager(0) { setWindowTitle(tr("OpenPilot Setup Wizard")); setOption(QWizard::IndependentPages, false); @@ -70,6 +70,14 @@ SetupWizard::SetupWizard(QWidget *parent) : QWizard(parent), VehicleConfiguratio createPages(); } +SetupWizard::~SetupWizard() +{ + if (m_vehicleTemplate != NULL) { + delete m_vehicleTemplate; + m_vehicleTemplate = NULL; + } +} + int SetupWizard::nextId() const { switch (currentId()) { @@ -189,14 +197,11 @@ int SetupWizard::nextId() const case CONTROLLER_CC3D: case CONTROLLER_REVO: case CONTROLLER_NANO: + case CONTROLLER_DISCOVERYF4: switch (getVehicleType()) { case VEHICLE_FIXEDWING: return PAGE_OUTPUT_CALIBRATION; - case CONTROLLER_DISCOVERYF4: - // Skip calibration. - return PAGE_OUTPUT_CALIBRATION; - default: return PAGE_BIAS_CALIBRATION; } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h index f46163792..894710ab9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.h @@ -40,6 +40,7 @@ class SetupWizard : public QWizard, public VehicleConfigurationSource { public: SetupWizard(QWidget *parent = 0); + ~SetupWizard(); int nextId() const; void setControllerType(SetupWizard::CONTROLLER_TYPE type) @@ -124,6 +125,15 @@ public: return m_radioSetting; } + void setVehicleTemplate(QJsonObject *templ) + { + m_vehicleTemplate = templ; + } + QJsonObject *getVehicleTemplate() const + { + return m_vehicleTemplate; + } + void setLevellingBias(accelGyroBias bias) { m_calibrationBias = bias; m_calibrationPerformed = true; @@ -193,6 +203,8 @@ private: GPS_TYPE m_gpsType; RADIO_SETTING m_radioSetting; + QJsonObject *m_vehicleTemplate; + bool m_calibrationPerformed; accelGyroBias m_calibrationBias; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h index 46c94ad09..1f4ecd027 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationsource.h @@ -29,6 +29,7 @@ #define VEHICLECONFIGURATIONSOURCE_H #include +#include #include "actuatorsettings.h" struct accelGyroBias { @@ -77,8 +78,9 @@ public: virtual VehicleConfigurationSource::AIRSPEED_TYPE getAirspeedType() const = 0; virtual VehicleConfigurationSource::GPS_TYPE getGpsType() const = 0; virtual VehicleConfigurationSource::RADIO_SETTING getRadioSetting() const = 0; + virtual QJsonObject *getVehicleTemplate() const = 0; - virtual bool isCalibrationPerformed() const = 0; + virtual bool isCalibrationPerformed() const = 0; virtual accelGyroBias getCalibrationBias() const = 0; virtual bool isMotorCalibrationPerformed() const = 0; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp index face12779..92c5c6486 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp @@ -43,12 +43,12 @@ #include "stabilizationsettingsbank3.h" #include "ekfconfiguration.h" -const char* VehicleTemplateExportDialog::EXPORT_BASE_NAME = "../share/openpilotgcs/cloudconfig"; -const char* VehicleTemplateExportDialog::EXPORT_FIXEDWING_NAME = "fixedwing"; -const char* VehicleTemplateExportDialog::EXPORT_MULTI_NAME = "multirotor"; -const char* VehicleTemplateExportDialog::EXPORT_HELI_NAME = "helicopter"; -const char* VehicleTemplateExportDialog::EXPORT_SURFACE_NAME = "surface"; -const char* VehicleTemplateExportDialog::EXPORT_CUSTOM_NAME = "custom"; +const char *VehicleTemplateExportDialog::EXPORT_BASE_NAME = "../share/openpilotgcs/cloudconfig"; +const char *VehicleTemplateExportDialog::EXPORT_FIXEDWING_NAME = "fixedwing"; +const char *VehicleTemplateExportDialog::EXPORT_MULTI_NAME = "multirotor"; +const char *VehicleTemplateExportDialog::EXPORT_HELI_NAME = "helicopter"; +const char *VehicleTemplateExportDialog::EXPORT_SURFACE_NAME = "surface"; +const char *VehicleTemplateExportDialog::EXPORT_CUSTOM_NAME = "custom"; VehicleTemplateExportDialog::VehicleTemplateExportDialog(QWidget *parent) : QDialog(parent), @@ -165,11 +165,11 @@ QString VehicleTemplateExportDialog::setupVehicleType() QString VehicleTemplateExportDialog::fixFilenameString(QString input, int truncate) { return input.replace(' ', "").replace('|', "").replace('/', "") - .replace('\\', "").replace(':', "").replace('"', "") - .replace('\'', "").replace('?', "").replace('*', "") - .replace('>', "").replace('<', "") - .replace('}', "").replace('{', "") - .left(truncate); + .replace('\\', "").replace(':', "").replace('"', "") + .replace('\'', "").replace('?', "").replace('*', "") + .replace('>', "").replace('<', "") + .replace('}', "").replace('{', "") + .left(truncate); } @@ -203,28 +203,29 @@ void VehicleTemplateExportDialog::accept() QByteArray bytes; QBuffer buffer(&bytes); buffer.open(QIODevice::WriteOnly); - m_image.scaled(IMAGE_SCALE_WIDTH, IMAGE_SCALE_HEIGHT, Qt::KeepAspectRatio).save(&buffer, "PNG"); - exportObject["photo"] = bytes.toBase64().data(); + m_image.scaled(IMAGE_SCALE_WIDTH, IMAGE_SCALE_HEIGHT, Qt::KeepAspectRatio, + Qt::SmoothTransformation).save(&buffer, "PNG"); + exportObject["photo"] = QString::fromLatin1(bytes.toBase64().data()); QJsonDocument saveDoc(exportObject); QString fileName = QString("%1/%2/%3-%4-%5-%6.optmpl") - .arg(EXPORT_BASE_NAME) - .arg(getTypeDirectory()) - .arg(fixFilenameString(ui->ForumNick->text(), 15)) - .arg(fixFilenameString(ui->Name->text(), 20)) - .arg(fixFilenameString(ui->Type->text(), 30)) - .arg(fixFilenameString(QUuid::createUuid().toString().right(12))); + .arg(EXPORT_BASE_NAME) + .arg(getTypeDirectory()) + .arg(fixFilenameString(ui->ForumNick->text(), 15)) + .arg(fixFilenameString(ui->Name->text(), 20)) + .arg(fixFilenameString(ui->Type->text(), 30)) + .arg(fixFilenameString(QUuid::createUuid().toString().right(12))); QFile saveFile(fileName); QDir dir; dir.mkpath(QFileInfo(saveFile).absoluteDir().absolutePath()); if (saveFile.open(QIODevice::WriteOnly)) { saveFile.write(saveDoc.toJson()); saveFile.close(); - QMessageBox::information(this, "Export", tr("Settings were exported to \n%1").arg(QFileInfo(saveFile).absoluteFilePath()),QMessageBox::Ok); + QMessageBox::information(this, "Export", tr("Settings were exported to \n%1").arg(QFileInfo(saveFile).absoluteFilePath()), QMessageBox::Ok); } else { QMessageBox::information(this, "Export", tr("Settings could not be exported to \n%1.\nPlease try again.") - .arg(QFileInfo(saveFile).absoluteFilePath()),QMessageBox::Ok); + .arg(QFileInfo(saveFile).absoluteFilePath()), QMessageBox::Ok); } QDialog::accept(); } @@ -243,15 +244,19 @@ void VehicleTemplateExportDialog::importImage() QString VehicleTemplateExportDialog::getTypeDirectory() { - switch(m_type) { + switch (m_type) { case VehicleConfigurationSource::VEHICLE_FIXEDWING: return EXPORT_FIXEDWING_NAME; + case VehicleConfigurationSource::VEHICLE_MULTI: return EXPORT_MULTI_NAME; + case VehicleConfigurationSource::VEHICLE_HELI: return EXPORT_HELI_NAME; + case VehicleConfigurationSource::VEHICLE_SURFACE: return EXPORT_SURFACE_NAME; + default: return EXPORT_CUSTOM_NAME; } @@ -260,7 +265,6 @@ QString VehicleTemplateExportDialog::getTypeDirectory() void VehicleTemplateExportDialog::updateStatus() { ui->acceptBtn->setEnabled(ui->Name->text().length() > 3 && ui->Owner->text().length() > 2 && - ui->ForumNick->text().length() > 2 && ui->Size->text().length() > 0 && - ui->Weight->text().length() > 0); - + ui->ForumNick->text().length() > 2 && ui->Size->text().length() > 0 && + ui->Weight->text().length() > 0); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h index 2e1d3a772..61f627be9 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.h @@ -40,12 +40,12 @@ class VehicleTemplateExportDialog : public QDialog { Q_OBJECT public: - static const char* EXPORT_BASE_NAME; - static const char* EXPORT_FIXEDWING_NAME; - static const char* EXPORT_MULTI_NAME; - static const char* EXPORT_HELI_NAME; - static const char* EXPORT_SURFACE_NAME; - static const char* EXPORT_CUSTOM_NAME; + static const char *EXPORT_BASE_NAME; + static const char *EXPORT_FIXEDWING_NAME; + static const char *EXPORT_MULTI_NAME; + static const char *EXPORT_HELI_NAME; + static const char *EXPORT_SURFACE_NAME; + static const char *EXPORT_CUSTOM_NAME; explicit VehicleTemplateExportDialog(QWidget *parent = 0); ~VehicleTemplateExportDialog(); @@ -58,7 +58,7 @@ private slots: void importImage(); private: - static const int IMAGE_SCALE_WIDTH = 500; + static const int IMAGE_SCALE_WIDTH = 500; static const int IMAGE_SCALE_HEIGHT = 500; Ui::VehicleTemplateExportDialog *ui; UAVObjectManager *m_uavoManager; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui index f03f7a33c..db58e94f4 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui @@ -301,14 +301,14 @@ - + QFrame::NoFrame QFrame::Raised - + 0 @@ -322,95 +322,166 @@ 0 - - - Comment: - - - - - - - - 0 - 0 - - - - Qt::ScrollBarAlwaysOn - - - Qt::ScrollBarAlwaysOff - - - Put comments here that doesn't fit in the categories above - - - - - - - - - - QFrame::NoFrame - - - QFrame::Raised - - - - 0 - - - 0 - - - 0 - - - 0 - - - - - Photo: - - - - - - - background-color: rgba(254, 254, 254, 0); - + QFrame::NoFrame - - - - 0 - 0 - 0 - - - - - false - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + QFrame::Raised + + + 0 + + + 0 + + + 0 + + + 0 + + + + + Comment: + + + + + + + + 0 + 0 + + + + Qt::ScrollBarAlwaysOn + + + Qt::ScrollBarAlwaysOff + + + Put comments here that doesn't fit in the categories above + + + + - - - - Select Image... + + + + QFrame::NoFrame + + QFrame::Raised + + + + 0 + + + 0 + + + 0 + + + 0 + + + + + Photo: + + + + + + + + 0 + 0 + + + + background-color: rgba(254, 254, 254, 0); + + + QFrame::NoFrame + + + QFrame::Sunken + + + + + 0 + 0 + 0 + + + + + false + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + QFrame::NoFrame + + + QFrame::Raised + + + + 0 + + + 0 + + + 0 + + + 0 + + + + + + 8 + + + + Photo will be scaled to 500x500px + + + + + + + Select Image... + + + + + + + + frame_4 + frame_3 From 7e789ccc694f3a20a33aeddfe8f701c9fcbf07a0 Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Thu, 25 Sep 2014 00:59:39 +0200 Subject: [PATCH 179/203] OP-1379 - Clear output pin at the end of dma cycle --- flight/pios/stm32f4xx/pios_ws2811.c | 1 + 1 file changed, 1 insertion(+) diff --git a/flight/pios/stm32f4xx/pios_ws2811.c b/flight/pios/stm32f4xx/pios_ws2811.c index b126a08d9..4b8e9d987 100644 --- a/flight/pios/stm32f4xx/pios_ws2811.c +++ b/flight/pios/stm32f4xx/pios_ws2811.c @@ -342,6 +342,7 @@ void PIOS_WS2811_Update() void PIOS_WS2811_DMA_irq_handler() { + pios_ws2811_pin_cfg->gpio->BSRRH = dmaSource[0]; pios_ws2811_cfg->timer->CR1 &= (uint16_t) ~TIM_CR1_CEN; DMA_ClearFlag(pios_ws2811_cfg->streamCh1, pios_ws2811_cfg->irq.flags); DMA_Cmd(pios_ws2811_cfg->streamCh2, DISABLE); From b68236fd72afabcd13acb7ee0738af603ad996b9 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Thu, 25 Sep 2014 07:30:35 +0200 Subject: [PATCH 180/203] OP-1508 Sbus fixes, new artwork from OP-1222 --- .../resources/connection-diagrams.svg | 41781 ++++++++++++---- 1 file changed, 32916 insertions(+), 8865 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg index f62e09121..fefc1c59a 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -2,6 +2,7 @@ + fit-margin-bottom="15" + inkscape:snap-grids="true" + showguides="false" + inkscape:guide-bbox="true" + inkscape:snap-global="true" + inkscape:snap-bbox="true" + inkscape:object-paths="true" + inkscape:snap-bbox-midpoints="true" + inkscape:snap-bbox-edge-midpoints="true"> + + + + + + + + + + + + + + + + + + + + + + + + + @@ -67,7 +188,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10073"> @@ -99,7 +220,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10105"> @@ -128,7 +249,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10165"> @@ -136,7 +257,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10181"> @@ -152,7 +273,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10213"> @@ -168,7 +289,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10269"> @@ -176,7 +297,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10285"> @@ -192,7 +313,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10317"> @@ -208,7 +329,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4329"> @@ -216,7 +337,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4345"> @@ -232,7 +353,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4377"> @@ -264,7 +385,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4437"> @@ -272,7 +393,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4453"> @@ -288,7 +409,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4485"> @@ -312,7 +433,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4925"> @@ -320,7 +441,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4941"> @@ -336,7 +457,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4973"> @@ -365,7 +486,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7903"> @@ -373,7 +494,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7919"> @@ -389,7 +510,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7951"> @@ -418,7 +539,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5467"> @@ -426,7 +547,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5483"> @@ -434,7 +555,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5499"> @@ -442,7 +563,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5515"> @@ -450,7 +571,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5553"> @@ -466,7 +587,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5585"> @@ -482,7 +603,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5617"> @@ -498,7 +619,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5649"> @@ -514,7 +635,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5681"> @@ -530,7 +651,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5713"> @@ -546,7 +667,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5745"> @@ -562,7 +683,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5777"> @@ -591,7 +712,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7159"> @@ -599,7 +720,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7175"> @@ -615,7 +736,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7207"> @@ -631,7 +752,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7239"> @@ -639,7 +760,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7255"> @@ -655,7 +776,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7287"> @@ -671,7 +792,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7319"> @@ -679,7 +800,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7335"> @@ -695,7 +816,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7367"> @@ -711,7 +832,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7423"> @@ -719,7 +840,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7439"> @@ -735,7 +856,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7471"> @@ -751,7 +872,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7503"> @@ -759,7 +880,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7519"> @@ -775,7 +896,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7551"> @@ -791,7 +912,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7583"> @@ -799,7 +920,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7599"> @@ -815,7 +936,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7631"> @@ -844,7 +965,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5841"> @@ -852,7 +973,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5857"> @@ -860,7 +981,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5873"> @@ -868,7 +989,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5889"> @@ -876,7 +997,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5905"> @@ -892,7 +1013,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5937"> @@ -908,7 +1029,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5969"> @@ -924,7 +1045,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6001"> @@ -940,7 +1061,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6033"> @@ -956,7 +1077,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6065"> @@ -972,7 +1093,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6097"> @@ -988,7 +1109,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6129"> @@ -1004,7 +1125,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6169"> @@ -1012,7 +1133,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6185"> @@ -1028,7 +1149,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6217"> @@ -1044,7 +1165,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6273"> @@ -1052,7 +1173,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6289"> @@ -1068,7 +1189,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6321"> @@ -1097,7 +1218,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5049"> @@ -1105,7 +1226,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5065"> @@ -1113,7 +1234,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5081"> @@ -1121,7 +1242,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5097"> @@ -1129,7 +1250,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5135"> @@ -1145,7 +1266,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5167"> @@ -1161,7 +1282,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5199"> @@ -1177,7 +1298,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5231"> @@ -1193,7 +1314,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5263"> @@ -1209,7 +1330,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5295"> @@ -1233,7 +1354,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5327"> @@ -1241,7 +1362,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5359"> @@ -1303,135 +1424,6 @@ stop-color="#FFF" id="stop6616" /> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + id="linearGradient4377-9"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -2181,79 +10289,18549 @@ image/svg+xml - + + inkscape:groupmode="layer" + id="layer35" + inkscape:label="background" + style="display:none" + sodipodi:insensitive="true" + transform="translate(9.5291677,71.377308)"> + + + + + + + + + + + + + + + Futaba + S-Bus + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + id="g5373" + transform="matrix(1,0,0,-1,0,2792.2535)"> + id="g5375" + clip-path="url(#clipPath5359-0)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10070-3)" /> @@ -3050,229 +30049,213 @@ + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#2f2d2e;fill-rule:nonzero" /> + style="fill:#c8c7c6;fill-rule:nonzero" /> + style="fill:#658acf;fill-rule:nonzero" /> + style="fill:#c8c7c6;fill-rule:nonzero" /> + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> - - + + + d="M 1810.9392,828.53631 L 2087.2614,828.53631 L 2334.5297,1177.7874" + stroke-miterlimit="4" + inkscape:connector-curvature="0" + style="opacity:0.6;fill:none;stroke:#ff0000;stroke-width:7.5;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;marker-start:url(#DotS);marker-end:url(#Arrow2Send)" /> + transform="translate(-4,0)" + id="g6079"> + id="g6081" + clip-path="url(#clipPath6065-8)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10102-8)" /> @@ -3848,12 +30824,12 @@ + transform="translate(-4,0)" + id="g6111"> + id="g6113" + clip-path="url(#clipPath6097-0)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10104-0)" /> @@ -3874,12 +30850,12 @@ + transform="translate(-4,0)" + id="g6143"> + id="g6145" + clip-path="url(#clipPath6129-2)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10106-6)" /> @@ -3900,39 +30876,39 @@ + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + id="g6175" + clip-path="url(#clipPath6169-2)" + style="opacity:0.5"> + id="g6177" + transform="translate(2191.2754,1327.0928)"> + style="fill:#b1c7eb;fill-rule:nonzero" /> + transform="translate(4,0)" + id="g6199"> + id="g6201" + clip-path="url(#clipPath6185-2)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10108-1)" /> @@ -3953,12 +30929,12 @@ + transform="translate(4,-4)" + id="g6231"> + id="g6233" + clip-path="url(#clipPath6217-8)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10110-9)" /> @@ -3979,58 +30955,58 @@ + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + id="g6279" + clip-path="url(#clipPath6273-5)" + style="opacity:0.5"> + id="g6281" + transform="translate(2193.8848,1514.2402)"> + style="fill:#b1c7eb;fill-rule:nonzero" /> + id="g6305" + clip-path="url(#clipPath6289-4)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10112-8)" /> @@ -4051,12 +31027,12 @@ + transform="translate(0,-4)" + id="g6335"> + id="g6337" + clip-path="url(#clipPath6321-0)" + style="opacity:0.69999701"> + style="fill:url(#radialGradient10114-4)" /> @@ -4077,124 +31053,166 @@ + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#48484a;fill-rule:nonzero" /> + style="fill:#ffffff;fill-rule:nonzero" /> + style="fill:#2f2d2e;fill-rule:nonzero" /> + style="fill:#c8c7c6;fill-rule:nonzero" /> + style="fill:#658acf;fill-rule:nonzero" /> + style="fill:#c8c7c6;fill-rule:nonzero" /> + + + + + + + id="layer31" + inkscape:label="hexax-frame" + style="display:none" + sodipodi:insensitive="true"> + style="display:inline" + transform="matrix(0.4,0,0,0.4,495.2018,97.747949)" + id="hexa-x"> - - - - + style="opacity:0.6;fill:none;stroke:#ff0000;stroke-width:7.5;stroke-linecap:round;stroke-linejoin:round;stroke-miterlimit:4;stroke-opacity:1;stroke-dasharray:none;marker-start:url(#DotS);marker-end:none" + d="M 470.3229,282.91329 L 504.4955,282.72845" + id="path12371" + inkscape:connector-curvature="0" /> + transform="matrix(2.1421356,1.2367625,1.2367625,-2.1421356,-5330.9322,661.46199)" + id="g19796"> + d="M 2440,1270 C 2443.33,1268.08 2447.05,1268.3 2448.32,1270.508 C 2449.59,1272.708 2447.924,1276.048 2444.6,1277.968 L 2145.6,1450.968 C 2142.28,1452.888 2138.55,1452.658 2137.28,1450.46 C 2136.01,1448.262 2137.679,1444.92 2141,1443 L 2440,1270 z" + id="path19798" /> + d="M 2440,1270 C 2443.33,1268.08 2447.05,1268.3 2448.32,1270.508 C 2449.59,1272.708 2447.924,1276.048 2444.6,1277.968 L 2145.6,1450.968 C 2142.28,1452.888 2138.55,1452.658 2137.28,1450.46 C 2136.01,1448.262 2137.679,1444.92 2141,1443 L 2440,1270 z" + id="path19800" /> + d="M 2450,1440 C 2453.33,1441.92 2454.99,1445.26 2453.72,1447.46 C 2452.45,1449.66 2448.73,1449.89 2445.4,1447.966 L 2146.4,1274.966 C 2143.08,1273.046 2141.41,1269.706 2142.68,1267.506 C 2143.95,1265.306 2147.68,1265.076 2151,1267.002 L 2450,1440.002 z" + id="path19802" /> + d="M 2450,1440 C 2453.33,1441.92 2454.99,1445.26 2453.72,1447.46 C 2452.45,1449.66 2448.73,1449.89 2445.4,1447.966 L 2146.4,1274.966 C 2143.08,1273.046 2141.41,1269.706 2142.68,1267.506 C 2143.95,1265.306 2147.68,1265.076 2151,1267.002 L 2450,1440.002 z" + id="path19804" /> + d="M 2300,1530 C 2300,1533.84 2297.94,1536.96 2295.4,1536.95 C 2292.86,1536.951 2290.8,1533.84 2290.8,1530 V 1185 C 2290.8,1181.16 2292.86,1178.05 2295.4,1178.05 C 2297.94,1178.05 2300,1181.17 2300,1185.01 L 2300,1530.01 z" + id="path19806" /> + d="M 2300,1530 C 2300,1533.84 2297.94,1536.96 2295.4,1536.95 C 2292.86,1536.951 2290.8,1533.84 2290.8,1530 V 1185 C 2290.8,1181.16 2292.86,1178.05 2295.4,1178.05 C 2297.94,1178.05 2300,1181.17 2300,1185.01 L 2300,1530.01 z" + id="path19808" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,968.3076,-983.2254)" + id="g19810"> + d="M 2310,1410 L 2312.77,1410 L 2312.77,1392.8 L 2329.97,1392.8 L 2329.97,1410 L 2333.04,1410 L 2321.54,1421.5 L 2310.04,1410 z" + id="path19812" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1056.4615,-1033.0581)" + id="g19814"> + style="opacity:0.5" + clip-path="url(#clipPath5841-3)" + id="g19816"> + transform="translate(2515.9893,1514.8203)" + id="g19818"> + d="M 0,0 C 33.2,-33.2 33.2,-87.1 -0.048,-120 C -33.248,-153.2 -87.148,-153.2 -120.048,-120 C -153.248,-86.8 -153.248,-33 -120.041,0 C -87.141,33.2 -33.241,33.2 -0.041,0" + id="path19820" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1081.1646,-940.42598)" + id="g19822"> + style="opacity:0.5" + clip-path="url(#clipPath5857-5)" + id="g19824"> + transform="translate(2355.4863,1607.2334)" + id="g19826"> + d="M 0,0 C 33.2,-33.2 33.2,-87.1 -0.047,-120 C -33.247,-153.2 -87.147,-153.2 -120.047,-120 C -153.247,-86.8 -153.247,-33 -120.039,0 C -87.139,33.2 -33.239,33.2 -0.039,0" + id="path19828" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,964.5025,-1057.7231)" + id="g19830"> + style="opacity:0.5" + clip-path="url(#clipPath5873-66)" + id="g19832"> + transform="translate(2516.0371,1330.8896)" + id="g19834"> + d="M 0,0 C 33.2,-33.2 33.2,-87.1 -0.051,-120 C -33.251,-153.2 -87.151,-153.2 -120.051,-120 C -153.251,-86.8 -153.251,-33 -120.043,0 C -87.143,33.2 -33.243,33.2 -0.043,0" + id="path19836" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,895.30485,-989.96338)" + id="g19838"> + style="opacity:0.5" + clip-path="url(#clipPath5889-3)" + id="g19840"> + transform="translate(2354.9951,1235.6455)" + id="g19842"> + d="M 0,0 C 33.2,-33.2 33.2,-87.1 -0.048,-120 C -33.248,-153.2 -87.148,-153.2 -120.048,-120 C -153.248,-86.8 -153.248,-33 -120.04,0 C -87.14,33.2 -33.24,33.2 -0.04,0" + id="path19844" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1058.4615,-1036.5222)" + id="g19846"> + style="opacity:0.69999701" + clip-path="url(#clipPath5905-9)" + id="g19848"> + d="M 2430,1450 C 2433.01,1440.23 2442.1,1433.1 2452.9,1433.1 C 2465.1,1433.1 2475.1,1442.21 2476.6,1454 H 2464.6 L 2500.2,1489.6 L 2535.8,1454 H 2524.5 C 2522.86,1422.9 2497.1,1398.2 2465.6,1398.2 C 2442,1398.19 2421.6,1412.1 2412.2,1432.2 L 2430,1450 z" + id="path19858" /> @@ -5480,12 +32488,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1058.4615,-1036.5222)" + id="g19860"> + style="opacity:0.69999701" + clip-path="url(#clipPath5937-4)" + id="g19862"> + d="M 2380,1460 C 2381.3,1491.4 2407.2,1516.5 2438.9,1516.5 C 2462.7,1516.51 2483.3,1502.4 2492.6,1482 L 2475.2,1464.6 C 2471.96,1473.95 2463.1,1480.7 2452.6,1480.7 C 2440.5,1480.71 2430.5,1471.71 2428.9,1460.1 L 2440,1460.1 L 2429.7,1449.8 L 2411.9,1432 L 2404.44,1424.54 L 2368.84,1460.14 H 2380.04 z" + id="path19872" /> @@ -5506,12 +32514,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,897.30485,-993.42748)" + id="g19874"> + style="opacity:0.69999701" + clip-path="url(#clipPath5969-7)" + id="g19876"> + d="M 2270,1170 C 2273.01,1160.22 2282.1,1153.1 2292.9,1153.1 C 2305.1,1153.1 2315.1,1162.21 2316.6,1174 H 2304.6 L 2340.2,1209.6 L 2375.8,1174 H 2364.5 C 2362.86,1142.9 2337.1,1118.2 2305.6,1118.2 C 2282,1118.189 2261.6,1132.1 2252.2,1152.2 L 2270,1170 z" + id="path19886" /> @@ -5532,12 +32540,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,897.30485,-993.42748)" + id="g19888"> + style="opacity:0.69999701" + clip-path="url(#clipPath6001-5)" + id="g19890"> + d="M 2220,1180 C 2221.3,1211.4 2247.2,1236.5 2278.9,1236.5 C 2302.7,1236.51 2323.3,1222.4 2332.6,1202 L 2315.2,1184.6 C 2311.96,1193.95 2303.1,1200.7 2292.6,1200.7 C 2280.5,1200.71 2270.5,1191.71 2268.9,1180.1 H 2280 L 2269.7,1169.8 L 2251.9,1152 L 2244.44,1144.54 L 2208.84,1180.14 H 2220.04 z" + id="path19900" /> @@ -5558,12 +32566,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,964.5025,-1057.7231)" + id="g19902"> + style="opacity:0.69999701" + clip-path="url(#clipPath6033-9)" + id="g19904"> + d="M 2480,1260 C 2476.99,1250.23 2467.9,1243.1 2457.1,1243.1 C 2444.9,1243.1 2434.9,1252.21 2433.4,1264 H 2445.4 L 2409.8,1299.6 L 2374.2,1264 H 2385.5 C 2387.14,1232.9 2412.9,1208.2 2444.4,1208.2 C 2468,1208.189 2488.4,1222.1 2497.8,1242.2 L 2480,1260 z" + id="path19914" /> @@ -5584,12 +32592,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,964.5025,-1057.7231)" + id="g19916"> + style="opacity:0.69999701" + clip-path="url(#clipPath6065-5)" + id="g19918"> + d="M 2530,1270 C 2528.7,1301.4 2502.8,1326.5 2471.1,1326.5 C 2447.3,1326.51 2426.7,1312.4 2417.4,1292 L 2434.8,1274.6 C 2438.04,1283.95 2446.9,1290.7 2457.4,1290.7 C 2469.5,1290.71 2479.5,1281.71 2481.1,1270.1 H 2470 L 2480.3,1259.8 L 2498.1,1242 L 2505.56,1234.54 L 2541.16,1270.14 H 2529.96 z" + id="path19928" /> @@ -5610,12 +32618,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1079.7005,-945.89008)" + id="g19930"> + style="opacity:0.69999701" + clip-path="url(#clipPath6097-7)" + id="g19932"> + d="M 2320,1540 C 2316.99,1530.23 2307.9,1523.1 2297.1,1523.1 C 2284.9,1523.11 2274.9,1532.21 2273.4,1544 H 2285.4 L 2249.8,1579.6 L 2214.2,1544 L 2225.5,1544.001 C 2227.14,1512.901 2252.9,1488.201 2284.4,1488.201 C 2308,1488.19 2328.4,1502.101 2337.8,1522.201 L 2320,1540.001 z" + id="path19942" /> @@ -5636,12 +32644,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1079.7005,-945.89008)" + id="g19944"> + style="opacity:0.69999701" + clip-path="url(#clipPath6129-8)" + id="g19946"> + d="M 2370,1550 C 2368.7,1581.4 2342.8,1606.5 2311.1,1606.5 C 2287.3,1606.51 2266.7,1592.4 2257.4,1572 L 2274.8,1554.6 C 2278.04,1563.95 2286.9,1570.7 2297.4,1570.7 C 2309.5,1570.71 2319.5,1561.71 2321.1,1550.1 H 2310 L 2320.3,1539.8 L 2338.1,1522 L 2345.56,1514.54 L 2381.16,1550.14 L 2369.96,1550.141 z" + id="path19956" /> @@ -5662,40 +32670,40 @@ + d="M 2301.6833,1565.5736 C 2314.5289,1562.1243 2322.1739,1548.8828 2318.7246,1536.0372 C 2315.2803,1523.1829 2302.0388,1515.5379 2289.1931,1518.9872 C 2276.3475,1522.4365 2268.7025,1535.678 2272.1518,1548.5236 C 2275.5874,1561.3729 2288.8376,1569.0229 2301.6783,1565.5823" + id="path19958" /> + d="M 2296.3628,1534.789 L 2290.9128,1544.2287 L 2289.5839,1540.9904 L 2286.749,1542.2405 L 2289.1889,1547.7945 L 2291.9862,1549.4095 L 2299.4362,1536.5057 L 2296.3791,1534.7407 z" + id="path19960" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,919.09419,-895.85226)" + id="g19962"> + style="opacity:0.5" + clip-path="url(#clipPath6169-9)" + id="g19964"> + transform="translate(2191.2754,1327.0928)" + id="g19966"> + d="M 0,0 C 33.2,-33.2 33.2,-87.1 -0.047,-120 C -33.247,-153.2 -87.147,-153.2 -120.047,-120 C -153.247,-86.8 -153.247,-33 -120.039,0 C -87.139,33.2 -33.239,33.2 -0.039,0" + id="path19968" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,924.55829,-897.31636)" + id="g19970"> + style="opacity:0.69999701" + clip-path="url(#clipPath6185-0)" + id="g19972"> + d="M 2150,1260 C 2146.99,1250.22 2137.9,1243.1 2127.1,1243.1 C 2114.9,1243.11 2104.9,1252.21 2103.4,1264 H 2115.4 L 2079.8,1299.6 L 2044.2,1264 H 2055.5 C 2057.14,1232.9 2082.9,1208.2 2114.4,1208.2 C 2138,1208.19 2158.4,1222.1 2167.8,1242.2 L 2150,1260 z" + id="path19982" /> @@ -5716,12 +32724,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,924.55829,-897.31636)" + id="g19984"> + style="opacity:0.69999701" + clip-path="url(#clipPath6217-2)" + id="g19986"> + d="M 2200,1270 C 2198.71,1301.4 2172.8,1326.5 2141.1,1326.5 C 2117.3,1326.51 2096.7,1312.4 2087.4,1292 L 2104.8,1274.6 C 2108.04,1283.95 2116.9,1290.7 2127.4,1290.7 C 2139.5,1290.71 2149.5,1281.71 2151.1,1270.1 H 2140 L 2150.3,1259.8 L 2168.1,1242 L 2175.56,1234.54 L 2211.16,1270.14 H 2199.96 z" + id="path19996" /> @@ -5742,60 +32750,60 @@ + d="M 2141.0488,1287.6603 C 2153.8944,1284.211 2161.5394,1270.9694 2158.0901,1258.1238 C 2154.6458,1245.2695 2141.4043,1237.6245 2128.5587,1241.0738 C 2115.713,1244.5231 2108.068,1257.7646 2111.5173,1270.6103 C 2114.9616,1283.4646 2128.2032,1291.1096 2141.0438,1287.6689" + id="path19998" /> + d="M 2139.1924,1258.8757 C 2136.8455,1257.5207 2134.1819,1257.6341 2132.4094,1259.3242 L 2134.6953,1261.7849 C 2135.484,1261.0509 2136.6642,1260.8547 2137.6688,1261.4347 C 2138.708,1262.0347 2139.2238,1263.1812 2138.5113,1264.4153 C 2137.6313,1265.9395 2135.9907,1265.5812 2134.7436,1264.8612 C 2133.8343,1264.3362 2132.6453,1263.3356 2131.9249,1262.4833 L 2127.9833,1270.0225 L 2135.8727,1274.5775 L 2137.3827,1271.9621 L 2132.2039,1268.9721 L 2133.2707,1266.8744 C 2133.6006,1267.185 2134.107,1267.5258 2134.488,1267.7458 C 2137.0688,1269.2358 2139.9473,1269.0502 2141.5073,1266.3482 C 2143.3123,1263.2219 2141.7287,1260.3446 2139.1999,1258.8846" + id="path20000" /> + d="M 2460.5442,1474.9993 C 2473.3899,1471.55 2481.0349,1458.3085 2477.5856,1445.4628 C 2474.1413,1432.6085 2460.8997,1424.9635 2448.0541,1428.4128 C 2435.2085,1431.8621 2427.5635,1445.1036 2431.0128,1457.9493 C 2434.4484,1470.7986 2447.6986,1478.4486 2460.5392,1475.0079" + id="path20002" /> + d="M 2452.7596,1440.4826 L 2451.2896,1443.0287 L 2453.6876,1450.4754 C 2453.9776,1451.443 2454.0491,1452.2891 2453.5996,1453.0686 C 2453.0746,1453.9779 2452.0731,1454.2426 2451.1075,1453.6851 C 2450.0855,1453.0951 2449.8807,1451.9099 2450.4138,1450.6865 L 2447.2556,1449.3966 C 2446.0466,1452.1627 2447.2556,1454.9299 2449.771,1456.3799 C 2452.1353,1457.7449 2455.1552,1457.8142 2456.7102,1455.1208 C 2457.7702,1453.2849 2457.3163,1451.591 2456.7482,1449.8544 L 2455.304,1445.4757 L 2460.5608,1448.5107 L 2462.0908,1445.8607 L 2452.7377,1440.4607 z" + id="path20004" /> + d="M 2300.8235,1195.6068 C 2313.6692,1192.1576 2321.3142,1178.916 2317.8649,1166.0704 C 2314.4206,1153.2161 2301.179,1145.5711 2288.3334,1149.0204 C 2275.4878,1152.4697 2267.8341,1165.7062 2271.2921,1178.5568 C 2274.7364,1191.4111 2287.9779,1199.0561 2300.8185,1195.6155" + id="path20006" /> + d="M 2292.2351,1174.4825 L 2292.1801,1174.4505 L 2291.873,1167.9224 L 2294.9821,1169.7174 L 2292.2321,1174.4805 z M 2299.2556,1168.8825 L 2300.7056,1166.371 L 2297.8478,1164.721 L 2296.3978,1167.2325 L 2290.3442,1163.7375 L 2288.8642,1166.301 L 2289.5987,1177.1288 L 2293.2533,1179.2388 L 2297.8083,1171.3494 L 2299.5923,1172.3794 L 2301.0223,1169.9025 L 2299.2556,1168.8825 z" + id="path20008" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1013.0175,-872.08396)" + id="g20010"> + style="opacity:0.5" + clip-path="url(#clipPath6273-8)" + id="g20012"> + transform="translate(2193.8848,1514.2402)" + id="g20014"> + d="M 0,0 C 33.2,-33.2 33.2,-87.1 -0.047,-120 C -33.247,-153.2 -87.147,-153.2 -120.047,-120 C -153.247,-86.8 -153.247,-33 -120.039,0 C -87.139,33.2 -33.239,33.2 -0.039,0" + id="path20016" /> + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1013.0175,-872.08396)" + id="g20018"> + style="opacity:0.69999701" + clip-path="url(#clipPath6289-3)" + id="g20020"> + d="M 2110,1450 C 2113.01,1440.23 2122.1,1433.1 2132.9,1433.1 C 2145.1,1433.1 2155.1,1442.21 2156.6,1454 H 2144.6 L 2180.2,1489.6 L 2215.8,1454 H 2204.5 C 2202.86,1422.9 2177.1,1398.2 2145.6,1398.2 C 2122,1398.19 2101.6,1412.1 2092.2,1432.2 L 2110,1450 z" + id="path20030" /> @@ -5816,12 +32824,12 @@ + transform="matrix(0.8660254,0.5,-0.5,0.8660254,1013.0175,-872.08396)" + id="g20032"> + style="opacity:0.69999701" + clip-path="url(#clipPath6321-6)" + id="g20034"> + d="M 2060,1460 C 2061.3,1491.4 2087.2,1516.5 2118.9,1516.5 C 2142.7,1516.5 2163.3,1502.4 2172.6,1482 L 2155.2,1464.6 C 2151.96,1473.95 2143.1,1480.7 2132.6,1480.7 C 2120.5,1480.71 2110.5,1471.71 2108.9,1460.1 H 2120 L 2109.7,1449.8 L 2091.9,1432 L 2084.44,1424.54 L 2048.84,1460.14 H 2060.04 z" + id="path20044" /> @@ -5842,6465 +32850,3508 @@ + d="M 2137.9721,1479.4375 C 2150.8177,1475.9882 2158.4714,1462.7517 2155.0134,1449.901 C 2151.5691,1437.0467 2138.3276,1429.4017 2125.482,1432.851 C 2112.6363,1436.3003 2104.9913,1449.5418 2108.4406,1462.3875 C 2111.8849,1475.2418 2125.1265,1482.8868 2137.9671,1479.4461" + id="path20046" /> + d="M 2132.1157,1457.5811 C 2130.9206,1456.8911 2130.5635,1455.5695 2131.2555,1454.3709 C 2131.8955,1453.2624 2133.2307,1452.7978 2134.4484,1453.5008 C 2135.6521,1454.1958 2135.9832,1455.5023 2135.2812,1456.7182 C 2134.6112,1457.8787 2133.316,1458.2741 2132.1157,1457.5811 M 2135.9175,1450.9541 C 2133.1202,1449.3391 2129.8126,1449.8082 2128.1876,1452.6227 C 2127.3076,1454.1469 2127.2046,1455.6694 2127.3252,1457.4365 L 2127.7592,1463.8647 L 2131.4485,1465.9947 L 2130.8275,1459.7703 L 2130.8275,1459.6478 C 2131.0115,1459.8753 2131.3628,1460.1508 2131.6529,1460.3183 C 2133.9045,1461.6183 2136.8454,1461.0646 2138.2954,1458.5531 C 2139.9854,1455.6259 2138.7005,1452.5516 2135.9205,1450.9466" + id="path20048" /> + d="M 2466.0494,1289.5215 C 2478.9037,1286.0772 2486.5487,1272.8357 2483.0907,1259.985 C 2479.6464,1247.1307 2466.4049,1239.4857 2453.5592,1242.935 C 2440.7136,1246.3843 2433.0599,1259.6209 2436.5179,1272.4715 C 2439.9622,1285.3258 2453.2037,1292.9708 2466.0444,1289.5302" + id="path20050" /> + d="M 2463.7425,1258.6545 C 2461.3956,1257.2995 2458.6839,1257.0965 2456.606,1259.0953 L 2459.0156,1261.4819 C 2459.746,1260.7627 2460.9625,1260.4697 2462.123,1261.1397 C 2462.9977,1261.6447 2463.7416,1262.6562 2463.0486,1263.8565 C 2462.2936,1265.1642 2460.7226,1264.7652 2459.4582,1264.0352 L 2458.6389,1263.5622 L 2457.3489,1265.7966 L 2458.2409,1266.3116 C 2459.3841,1266.9716 2460.3246,1267.9026 2459.6126,1269.1358 C 2459.0776,1270.0624 2458.0106,1270.1046 2457.1731,1269.6211 C 2456.2985,1269.1161 2455.9311,1268.1523 2456.2365,1267.1635 L 2453.0179,1266.1782 C 2452.3862,1268.7003 2453.7866,1270.9868 2455.9257,1272.2218 C 2458.1947,1273.5318 2461.125,1273.6763 2462.555,1271.1995 C 2463.375,1269.7792 2463.0757,1268.1976 2462.0049,1267.1522 L 2462.0359,1267.0982 C 2463.6903,1267.5927 2465.4027,1266.9867 2466.2327,1265.5491 C 2467.8627,1262.7258 2466.0986,1260.0214 2463.7343,1258.6564" + id="path20052" /> + d="M 2253.9161,1368.6254 L 2307.6963,1399.6754 C 2309.1079,1400.4904 2310.9111,1400.0072 2311.7261,1398.5956 L 2342.7761,1344.8154 C 2343.5911,1343.4038 2343.1129,1341.592 2341.7013,1340.777 L 2287.9211,1309.727 C 2286.5095,1308.912 2284.7064,1309.3951 2283.8864,1310.8154 L 2252.8364,1364.5956 C 2252.0214,1366.0072 2252.5045,1367.8104 2253.9161,1368.6254" + id="path20054" /> + d="M 2293.4328,1352.1805 L 2295.7253,1342.6499 L 2303.896,1342.8177 L 2300.8988,1353.789 L 2293.4228,1352.1978 z M 2283.4326,1365.9213 L 2286.9586,1353.7542 L 2289.0285,1354.089 L 2300.6264,1356.2009 L 2298.2708,1366.2609 L 2283.4774,1365.8837 z M 2287.9177,1383.7529 C 2286.9108,1383.1969 2286.2638,1382.2576 2286.5924,1380.8284 L 2289.8937,1367.0305 L 2297.2892,1367.2011 L 2294.4141,1377.7809 C 2294.4821,1379.2518 2295.7055,1379.4041 2297.1437,1379.3731 L 2308.6225,1378.6911 C 2309.7073,1378.5103 2310.665,1377.9535 2311.3767,1376.6208 L 2315.059,1369.0589 C 2315.5511,1367.9805 2315.2886,1367.0091 2314.7625,1366.8323 L 2297.4839,1366.3597 L 2300.2543,1356.1813 L 2304.1286,1356.8708 L 2304.1386,1356.8608 L 2320.0472,1359.7064 C 2322.4169,1360.1219 2322.9238,1363.284 2321.1231,1366.5629 L 2314.4794,1378.2001 C 2312.7819,1381.0422 2310.5091,1381.7969 2308.4785,1382.114 L 2292.5299,1384.3377 C 2291.1794,1384.5568 2289.2387,1384.4582 2287.921,1383.7205" + id="path20056" /> + d="M 2281.2367,1361.3049 L 2279.7242,1361.3046 L 2278.5987,1365.5738 L 2275.275,1365.4908 L 2271.0678,1359.8979 L 2262.1938,1357.4881 L 2271.7104,1356.8048 L 2278.0901,1351.9549 L 2282.2142,1352.8118 L 2280.9354,1357.5467 L 2282.1072,1357.997 L 2281.2368,1361.3165 z" + id="path20058" /> + d="M 2324.2174,1346.86 L 2326.4344,1348.14 C 2326.6769,1348.28 2326.921,1348.2973 2327.1848,1348.23 C 2327.3163,1348.204 2327.4367,1348.146 2327.528,1348.0656 C 2327.6312,1347.9886 2327.7246,1347.895 2327.7951,1347.7729 L 2328.2521,1346.9814 C 2328.3201,1346.8644 2328.3557,1346.734 2328.376,1346.5968 C 2328.396,1346.4846 2328.386,1346.3588 2328.339,1346.2312 C 2328.267,1345.9657 2328.1291,1345.7648 2327.8866,1345.6248 L 2325.6696,1344.3448 C 2325.4315,1344.2073 2325.1806,1344.1837 2324.9208,1344.2578 C 2324.7863,1344.2828 2324.6738,1344.3358 2324.577,1344.4034 C 2324.478,1344.4954 2324.3786,1344.589 2324.3111,1344.706 L 2323.8541,1345.4975 C 2323.7841,1345.6196 2323.7533,1345.75 2323.729,1345.8722 C 2323.715,1345.9967 2323.719,1346.1284 2323.767,1346.2566 C 2323.835,1346.5151 2323.9797,1346.7223 2324.2178,1346.8598 M 2313.4791,1340.6598 L 2315.6961,1341.9398 C 2315.936,1342.0783 2316.1809,1342.0961 2316.4413,1342.0268 C 2316.7002,1341.9598 2316.9211,1341.8119 2317.0586,1341.5737 L 2317.5156,1340.7822 C 2317.6541,1340.5423 2317.6772,1340.2681 2317.5956,1340.028 C 2317.5326,1339.7697 2317.39,1339.5641 2317.1597,1339.4311 L 2314.068,1337.6461 L 2313.572,1338.5052 L 2313.3115,1338.9564 L 2313.115,1339.2967 C 2313.044,1339.4188 2313.0108,1339.5472 2312.9942,1339.6739 C 2312.9812,1339.7989 2312.9942,1339.9341 2313.0352,1340.0598 C 2313.0922,1340.3123 2313.2357,1340.5185 2313.479,1340.659 M 2300.4887,1333.159 L 2302.697,1334.434 C 2302.9456,1334.5775 2303.1896,1334.5948 2303.4535,1334.528 C 2303.5797,1334.499 2303.6959,1334.438 2303.7941,1334.3621 C 2303.899,1334.2861 2303.9881,1334.19 2304.0546,1334.0748 L 2300.1228,1331.8048 C 2300.0568,1331.92 2300.0209,1332.0474 2300.0035,1332.1736 C 2299.9895,1332.2981 2299.9935,1332.4293 2300.0355,1332.5545 C 2300.1045,1332.8135 2300.2559,1333.0247 2300.4897,1333.1597 M 2293.9859,1329.4047 L 2296.1856,1330.6747 C 2296.4289,1330.8152 2296.6885,1330.8415 2296.9533,1330.775 C 2297.2174,1330.712 2297.4096,1330.5466 2297.5471,1330.3084 L 2298.0041,1329.5169 C 2298.1426,1329.277 2298.1944,1329.0193 2298.1073,1328.7762 C 2298.0343,1328.5102 2297.8809,1328.3003 2297.6376,1328.1598 L 2296.0008,1327.2148 L 2294.5805,1326.3948 L 2294.0845,1327.2539 L 2293.824,1327.7051 L 2293.6275,1328.0454 C 2293.5575,1328.1675 2293.5103,1328.2884 2293.4972,1328.4171 C 2293.4972,1328.5476 2293.4972,1328.6803 2293.5352,1328.8015 C 2293.5962,1329.056 2293.7495,1329.2682 2293.9929,1329.4087 M 2287.4804,1325.6487 L 2289.6801,1326.9187 C 2289.92,1327.0572 2290.1857,1327.087 2290.4435,1327.0167 C 2290.5637,1326.9847 2290.6789,1326.9227 2290.7858,1326.8518 C 2290.889,1326.7748 2290.9729,1326.6757 2291.0434,1326.5536 L 2291.5004,1325.7621 C 2291.5684,1325.6451 2291.6135,1325.5202 2291.6338,1325.383 C 2291.6338,1325.2618 2291.6338,1325.139 2291.5978,1325.0179 C 2291.5318,1324.7559 2291.3723,1324.5425 2291.1324,1324.404 L 2290.857,1324.245 L 2288.9344,1323.135 C 2288.6902,1322.994 2288.4359,1322.9684 2288.1674,1323.037 C 2288.0519,1323.073 2287.9351,1323.123 2287.8366,1323.1901 C 2287.7236,1323.2741 2287.6425,1323.3782 2287.575,1323.4952 L 2287.118,1324.2867 C 2287.048,1324.4088 2286.9991,1324.5287 2286.9886,1324.6589 C 2286.9766,1324.7844 2286.9886,1324.9186 2287.0136,1325.0358 C 2287.0896,1325.2993 2287.2384,1325.5085 2287.4826,1325.6495 M 2323.6821,1347.7502 C 2323.4405,1347.6107 2323.2363,1347.4362 2323.0757,1347.2084 C 2322.9188,1347.0162 2322.8053,1346.7728 2322.7497,1346.5352 C 2322.6767,1346.275 2322.6587,1346.0141 2322.6807,1345.7425 C 2322.7147,1345.469 2322.8186,1345.2217 2322.9551,1344.9853 L 2323.4201,1344.1799 C 2323.5606,1343.9365 2323.723,1343.7231 2323.9397,1343.5619 C 2324.162,1343.4108 2324.3949,1343.2993 2324.6556,1343.2339 C 2324.8892,1343.1629 2325.1567,1343.1399 2325.4046,1343.1749 C 2325.6812,1343.2019 2325.9324,1343.2948 2326.174,1343.4343 L 2328.5036,1344.7793 C 2328.7435,1344.9178 2328.9514,1345.0898 2329.1086,1345.3134 C 2329.266,1345.5128 2329.3813,1345.7571 2329.4473,1346.0008 C 2329.5163,1346.2567 2329.5353,1346.5137 2329.5113,1346.7788 C 2329.4713,1347.042 2329.3825,1347.2979 2329.242,1347.5413 L 2328.777,1348.3467 C 2328.6405,1348.5831 2328.4633,1348.7879 2328.2523,1348.9594 C 2328.0332,1349.117 2327.7991,1349.2324 2327.5418,1349.3021 C 2327.2978,1349.3671 2327.0285,1349.3891 2326.7801,1349.3471 C 2326.5069,1349.3241 2326.252,1349.2339 2326.0121,1349.0954 L 2323.6825,1347.7504 z M 2299.953,1334.0502 C 2299.7148,1333.9127 2299.5098,1333.7377 2299.3449,1333.5074 C 2299.1845,1333.3132 2299.0753,1333.0723 2299.0145,1332.8317 C 2298.9475,1332.575 2298.9235,1332.3101 2298.9525,1332.043 C 2298.9855,1331.7708 2299.0714,1331.5251 2299.2099,1331.2852 L 2299.6749,1330.4798 C 2299.8134,1330.2399 2299.987,1330.0353 2300.2075,1329.8693 C 2300.4231,1329.712 2300.6659,1329.5993 2300.9205,1329.5304 C 2301.1593,1329.4624 2301.4225,1329.4374 2301.6739,1329.4734 C 2301.9548,1329.5024 2302.2068,1329.5963 2302.445,1329.7338 L 2306.0044,1331.7888 L 2305.4844,1332.6895 L 2301.977,1330.6645 C 2301.7431,1330.5295 2301.4854,1330.5019 2301.2247,1330.5755 C 2301.1216,1330.6065 2301.0295,1330.6475 2300.9403,1330.7081 C 2300.8433,1330.7631 2300.76,1330.8384 2300.6962,1330.917 L 2305.5719,1333.732 L 2305.0419,1334.65 C 2304.9034,1334.8898 2304.7303,1335.0855 2304.5238,1335.2573 C 2304.2995,1335.4118 2304.0723,1335.5313 2303.8081,1335.5969 C 2303.5615,1335.6599 2303.2957,1335.6849 2303.0404,1335.6389 C 2302.7801,1335.6239 2302.5252,1335.5331 2302.2723,1335.3871 L 2299.9514,1334.0471 z M 2286.9626,1326.5502 C 2286.7115,1326.4052 2286.5065,1326.2302 2286.3597,1326.0104 C 2286.1864,1325.8087 2286.0824,1325.5708 2286.0103,1325.3237 C 2285.9463,1325.0685 2285.9233,1324.8046 2285.9513,1324.5365 C 2285.9913,1324.2665 2286.0788,1324.0097 2286.2153,1323.7733 L 2286.6803,1322.9679 C 2286.8208,1322.7245 2286.9997,1322.5206 2287.2103,1322.3559 C 2287.4266,1322.2013 2287.6647,1322.0928 2287.9167,1322.0224 C 2288.1668,1321.9614 2288.4248,1321.9324 2288.6891,1321.9764 C 2288.9519,1321.9954 2289.2039,1322.0888 2289.455,1322.2338 L 2291.1957,1323.2388 L 2291.7708,1323.5708 L 2294.1956,1324.9708 L 2295.1906,1323.2474 L 2296.1519,1323.8024 L 2295.1569,1325.5258 L 2295.9606,1325.9898 L 2296.2724,1326.1698 L 2298.2815,1327.3298 C 2298.5266,1327.4713 2298.7302,1327.6408 2298.8796,1327.8599 C 2299.0517,1328.0678 2299.1566,1328.3061 2299.2339,1328.5563 C 2299.3069,1328.8142 2299.3219,1329.0692 2299.2899,1329.3298 C 2299.2519,1329.594 2299.1697,1329.8539 2299.0292,1330.0973 L 2298.5642,1330.9027 C 2298.4277,1331.1391 2298.2436,1331.3399 2298.0309,1331.5104 C 2297.8196,1331.6725 2297.589,1331.7899 2297.3282,1331.8576 C 2297.0729,1331.9156 2296.814,1331.9436 2296.5509,1331.8936 C 2296.2855,1331.8756 2296.0349,1331.7874 2295.7898,1331.6459 L 2293.4689,1330.3059 C 2293.2255,1330.1654 2293.0214,1329.9909 2292.8651,1329.7656 C 2292.6987,1329.5679 2292.5921,1329.3285 2292.52,1329.0814 C 2292.453,1328.8242 2292.429,1328.5603 2292.465,1328.2967 C 2292.498,1328.0227 2292.5821,1327.7639 2292.7186,1327.5275 L 2293.6736,1325.8734 L 2292.7902,1325.3634 C 2292.7802,1325.4304 2292.7802,1325.5068 2292.7702,1325.57 C 2292.7432,1325.8408 2292.6561,1326.0977 2292.5156,1326.341 L 2292.0506,1327.1464 C 2291.9141,1327.3829 2291.7352,1327.5867 2291.5112,1327.7507 C 2291.3094,1327.9182 2291.0684,1328.0297 2290.8189,1328.1038 C 2290.5636,1328.1618 2290.3004,1328.1878 2290.0434,1328.1408 C 2289.7666,1328.1158 2289.5135,1328.0265 2289.2701,1327.886 L 2286.9492,1326.546 z M 2320.1965,1339.9874 L 2321.1491,1340.5374 L 2318.6491,1344.8675 L 2317.6965,1344.3175 L 2320.1965,1339.9874 z M 2306.4382,1337.8175 C 2306.2018,1337.681 2306.0009,1337.4969 2305.8442,1337.2644 C 2305.6907,1337.0742 2305.5789,1336.8318 2305.5129,1336.5881 C 2305.4459,1336.3315 2305.4249,1336.0685 2305.4479,1335.798 C 2305.4909,1335.5317 2305.5815,1335.2885 2305.72,1335.0487 L 2307.2,1332.4852 L 2308.144,1333.0302 L 2306.669,1335.585 C 2306.5325,1335.8214 2306.5095,1336.0853 2306.575,1336.3473 C 2306.599,1336.4652 2306.668,1336.5831 2306.7309,1336.6832 C 2306.8099,1336.7888 2306.9044,1336.8688 2307.023,1336.9373 L 2309.2487,1338.2223 C 2309.363,1338.2883 2309.4875,1338.3348 2309.6053,1338.3427 C 2309.7375,1338.3557 2309.8781,1338.3577 2309.9837,1338.3157 C 2310.2513,1338.2457 2310.4622,1338.0908 2310.5987,1337.8544 L 2312.0737,1335.2996 L 2312.3387,1335.4526 L 2313.0186,1335.8451 L 2313.6923,1336.2341 L 2314.6873,1334.5107 L 2315.64,1335.0607 L 2314.645,1336.7841 L 2315.4478,1337.2476 L 2317.4396,1338.3976 L 2317.7921,1338.6011 C 2318.0216,1338.7336 2318.2295,1338.9056 2318.3893,1339.1307 C 2318.5415,1339.3271 2318.6568,1339.5715 2318.7228,1339.8151 C 2318.7888,1340.0691 2318.8158,1340.3305 2318.7868,1340.5936 C 2318.7518,1340.8599 2318.651,1341.1087 2318.5105,1341.3521 L 2318.0455,1342.1575 C 2317.909,1342.3939 2317.744,1342.6058 2317.5278,1342.7742 C 2317.3121,1342.9338 2317.0702,1343.0447 2316.8164,1343.1164 C 2316.5724,1343.1814 2316.3031,1343.2034 2316.0599,1343.1644 C 2315.7841,1343.1404 2315.5292,1343.0497 2315.2997,1342.9172 L 2312.9528,1341.5622 C 2312.7111,1341.4227 2312.507,1341.2483 2312.3499,1341.0224 C 2312.199,1340.8337 2312.0916,1340.5939 2312.0186,1340.3462 C 2311.9496,1340.088 2311.9276,1339.8251 2311.9506,1339.554 C 2311.9916,1339.2846 2312.0807,1339.0287 2312.2172,1338.7923 L 2313.1722,1337.1382 L 2312.4984,1336.7492 L 2311.5434,1338.4033 L 2311.5434,1338.4133 C 2311.4049,1338.6531 2311.231,1338.8483 2311.0305,1339.0236 C 2310.8053,1339.1776 2310.5721,1339.2936 2310.3148,1339.3632 C 2310.0665,1339.4252 2309.7972,1339.4482 2309.548,1339.4052 C 2309.2873,1339.3952 2309.0265,1339.3142 2308.7832,1339.1738 L 2306.4449,1337.8238 z M 2327.8934,1351.8559 L 2328.5034,1350.7993 L 2328.0791,1350.5543 L 2328.6041,1349.645 L 2329.0284,1349.89 L 2330.0934,1348.0454 C 2330.2339,1347.802 2330.4198,1347.6022 2330.6243,1347.4339 C 2330.8432,1347.2808 2331.0709,1347.1664 2331.3255,1347.0974 C 2331.5825,1347.0404 2331.8379,1347.0104 2332.1031,1347.0544 C 2332.3642,1347.0724 2332.617,1347.1663 2332.869,1347.3118 L 2333.5541,1347.7073 L 2333.0341,1348.608 L 2332.3612,1348.2195 C 2332.1148,1348.1061 2331.8602,1348.0792 2331.6261,1348.1645 C 2331.504,1348.1845 2331.3851,1348.2455 2331.289,1348.3244 C 2331.194,1348.3904 2331.1167,1348.4928 2331.0502,1348.608 L 2329.9902,1350.444 L 2331.4798,1351.304 L 2331.3683,1351.4971 L 2330.9533,1352.2159 L 2329.4637,1351.3559 L 2328.8537,1352.4124 L 2327.8924,1351.8574 z M 2318.2589,1346.9435 L 2320.7389,1342.648 C 2320.8774,1342.4081 2321.0613,1342.2095 2321.2767,1342.0405 C 2321.4853,1341.8792 2321.7151,1341.759 2321.9711,1341.7036 C 2322.2333,1341.6436 2322.4818,1341.6146 2322.7612,1341.6546 C 2323.0222,1341.6726 2323.2664,1341.7616 2323.5141,1341.9046 L 2323.7055,1342.0151 L 2323.1855,1342.9158 L 2323.0114,1342.8153 C 2322.772,1342.7059 2322.533,1342.688 2322.2764,1342.7603 C 2322.1612,1342.7843 2322.0449,1342.8473 2321.9514,1342.9271 C 2321.8435,1342.9861 2321.7765,1343.0941 2321.71,1343.2092 L 2319.23,1347.5047 L 2318.2601,1346.9447 z M 2317.1981,1345.0608 L 2318.1507,1345.6108 L 2317.6007,1346.5635 L 2316.6481,1346.0135 L 2317.1981,1345.0608 z" + id="path20060" /> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + sodipodi:nodetypes="cccc" /> + sodipodi:nodetypes="cccc" /> + stroke-miterlimit="4" + d="M 470.3229,324.24379 L 504.4955,324.76199 M 611.9955,324.24379 L 900.48286,324.24379 L 982.43382,234.07311" + id="path19792" /> + stroke-miterlimit="4" + d="M 470.3229,124.47969 L 764.4955,123.9243 L 764.4955,-77.805374 L 1490.5185,-76.213574 L 1491.0211,115.9054" + id="path19786" /> + stroke-miterlimit="4" + d="M 470.3229,163.05484 L 718.623,162.87055 L 718.623,138.6481 M 718.622,100.44502 L 716.8843,-120.50867 L 1732.1087,-118.61107 L 1733.5546,504.86806" + id="path19788" /> - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - Spectrum - Satellite - - - - - - - - - - - - Futaba - S-Bus - - - - - - - - - - - - PPM Signal - - - - - - - - - - - - - - - - - Throttle - Roll - Pitch - Yaw - Flight Mode - - + stroke-miterlimit="4" + d="M 470.3229,204.38534 L 553.9805,204.38534 L 556.1914,749.2282 L 1441.0819,965.31207" + id="path19790" /> + + + From b0e337c540cd0b9088bc89cae6abc77b28989911 Mon Sep 17 00:00:00 2001 From: m_thread Date: Thu, 25 Sep 2014 23:16:13 +0200 Subject: [PATCH 181/203] OP-1222 Added UUID to template file for identification. Implemented the code to apply the template settings. Fixed tab order in template export dialog. Extended support for parsing and applying json data in uavobjectmanager. --- .../pages/airframeinitialtuningpage.cpp | 32 +++++++++---------- .../vehicleconfigurationhelper.cpp | 18 +++++++++++ .../setupwizard/vehicleconfigurationhelper.h | 1 + .../vehicletemplateexportdialog.cpp | 7 ++-- .../vehicletemplateexportdialog.ui | 19 +++++++++++ .../plugins/uavobjects/uavobjectmanager.cpp | 5 ++- .../src/plugins/uavobjects/uavobjectmanager.h | 2 +- 7 files changed, 63 insertions(+), 21 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp index bae342554..d3383f07c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp @@ -82,6 +82,9 @@ bool AirframeInitialTuningPage::validatePage() if (ui->templateList->currentRow() >= 0) { templ = ui->templateList->item(ui->templateList->currentRow())->data(Qt::UserRole + 1).value(); } + if (getWizard()->getVehicleTemplate() != NULL) { + delete getWizard()->getVehicleTemplate(); + } getWizard()->setVehicleTemplate(new QJsonObject(*templ)); return true; } @@ -114,8 +117,11 @@ void AirframeInitialTuningPage::updateDescription(QJsonObject *templ) if (templ != NULL) { QString description; description.append("").append(tr("Name of Vehicle: ")).append("").append(templ->value("name").toString()).append("
"); - description.append("").append(tr("Name of Owner: ")).append("").append(templ->value("owner").toString()) - .append(" (").append(templ->value("nick").toString()).append(")").append("
"); + description.append("").append(tr("Name of Owner: ")).append("").append(templ->value("owner").toString()); + if (templ->value("nick") != "") { + description.append(" (").append(templ->value("nick").toString()).append(")"); + } + description.append("
"); description.append("").append(tr("Size: ")).append("").append(templ->value("size").toString()).append("
"); description.append("").append(tr("Weight: ")).append("").append(templ->value("weight").toString()).append("
"); description.append("").append(tr("Motor(s): ")).append("").append(templ->value("motor").toString()).append("
"); @@ -156,26 +162,19 @@ void AirframeInitialTuningPage::loadValidFiles() QStringList files = templateDir.entryList(); foreach(QString fileName, files) { QFile file(QString("%1/%2").arg(templateDir.absolutePath()).arg(fileName)); - if (file.open(QFile::ReadOnly)) { QByteArray jsonData = file.readAll(); QJsonDocument templateDoc = QJsonDocument::fromJson(jsonData); QJsonObject json = templateDoc.object(); if (json["type"].toInt() == getWizard()->getVehicleType() && json["subtype"].toInt() == getWizard()->getVehicleSubType()) { - QString nameKey = getTemplateKey(&json); - int index = 0; - while (true) { - if (!m_templates.contains(nameKey)) { - m_templates[nameKey] = new QJsonObject(json); - break; - } else { - nameKey = QString("%1 - %2").arg(nameKey).arg(++index); - } + QString uuid = json["uuid"].toString(); + if (!m_templates.contains(uuid)) { + m_templates[json["uuid"].toString()] = new QJsonObject(json); } } - file.close(); } + file.close(); } } @@ -185,15 +184,16 @@ void AirframeInitialTuningPage::setupTemplateList() item->setData(Qt::UserRole + 1, QVariant::fromValue((QJsonObject *)NULL)); foreach(QString templ, m_templates.keys()) { - item = new QListWidgetItem(templ, ui->templateList); - item->setData(Qt::UserRole + 1, QVariant::fromValue(m_templates[templ])); + QJsonObject *json = m_templates[templ]; + item = new QListWidgetItem(json->value("name").toString(), ui->templateList); + item->setData(Qt::UserRole + 1, QVariant::fromValue(json)); } ui->templateList->setCurrentRow(0); } QString AirframeInitialTuningPage::getTemplateKey(QJsonObject *templ) { - return QString("%1 - %2").arg(templ->value("nick").toString()).arg(templ->value("name").toString()); + return QString(templ->value("name").toString()); } void AirframeInitialTuningPage::resizeEvent(QResizeEvent *) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index d1155a74d..2cfa8df32 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -42,6 +42,7 @@ #include "gpssettings.h" #include "airspeedsettings.h" #include +#include const qint16 VehicleConfigurationHelper::LEGACY_ESC_FREQUENCE = 50; const qint16 VehicleConfigurationHelper::RAPID_ESC_FREQUENCE = 400; @@ -82,6 +83,8 @@ bool VehicleConfigurationHelper::setupVehicle(bool save) applyStabilizationConfiguration(); applyManualControlDefaults(); + applyTemplateSettings(); + bool result = saveChangesToController(save); emit saveProgress(m_modifiedObjects.count() + 1, ++m_progress, result ? tr("Done!") : tr("Failed!")); return result; @@ -747,6 +750,21 @@ void VehicleConfigurationHelper::applyManualControlDefaults() addModifiedObject(mcSettings, tr("Writing manual control defaults")); } +void VehicleConfigurationHelper::applyTemplateSettings() +{ + if (m_configSource->getVehicleTemplate() != NULL) { + QJsonObject* json = m_configSource->getVehicleTemplate(); + QList updatedObjects; + m_uavoManager->fromJson(*json, &updatedObjects); + foreach (UAVObject* object, updatedObjects) { + UAVDataObject *dataObj = dynamic_cast(object); + if (dataObj != NULL) { + addModifiedObject(dataObj, QString(tr("Writing template settings for %1")).arg(object->getName())); + } + } + } +} + bool VehicleConfigurationHelper::saveChangesToController(bool save) { qDebug() << "Saving modified objects to controller. " << m_modifiedObjects.count() << " objects in found."; diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h index 5b692c30c..750697a41 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.h @@ -87,6 +87,7 @@ private: void applySensorBiasConfiguration(); void applyStabilizationConfiguration(); void applyManualControlDefaults(); + void applyTemplateSettings(); void applyMixerConfiguration(mixerChannelSettings channels[]); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp index 92c5c6486..9e85e5158 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.cpp @@ -199,6 +199,8 @@ void VehicleTemplateExportDialog::accept() exportObject["propeller"] = ui->Propeller->text(); exportObject["controller"] = ui->Controllers->currentText(); exportObject["comment"] = ui->Comment->document()->toPlainText(); + QUuid uuid = QUuid::createUuid(); + exportObject["uuid"] = uuid.toString(); QByteArray bytes; QBuffer buffer(&bytes); @@ -209,13 +211,12 @@ void VehicleTemplateExportDialog::accept() QJsonDocument saveDoc(exportObject); - QString fileName = QString("%1/%2/%3-%4-%5-%6.optmpl") + QString fileName = QString("%1/%2/%3-%4-%5.optmpl") .arg(EXPORT_BASE_NAME) .arg(getTypeDirectory()) - .arg(fixFilenameString(ui->ForumNick->text(), 15)) .arg(fixFilenameString(ui->Name->text(), 20)) .arg(fixFilenameString(ui->Type->text(), 30)) - .arg(fixFilenameString(QUuid::createUuid().toString().right(12))); + .arg(fixFilenameString(uuid.toString().right(12))); QFile saveFile(fileName); QDir dir; dir.mkpath(QFileInfo(saveFile).absoluteDir().absolutePath()); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui index db58e94f4..4711d3fe5 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicletemplateexportdialog.ui @@ -540,6 +540,25 @@
+ + Type + Name + Owner + ForumNick + Size + Weight + Motor + Esc + Servo + Battery + Propeller + Controllers + Comment + ImportButton + acceptBtn + cancelBtn + Photo + diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.cpp b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.cpp index 8683f905b..a90b18dd6 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.cpp +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.cpp @@ -340,7 +340,7 @@ void UAVObjectManager::toJson(QJsonObject &jsonObject, const QList jsonObject["objects"] = jObjects; } -void UAVObjectManager::fromJson(const QJsonObject &jsonObject) +void UAVObjectManager::fromJson(const QJsonObject &jsonObject, QList *updatedObjects) { QJsonArray jObjects = jsonObject["objects"].toArray(); @@ -349,6 +349,9 @@ void UAVObjectManager::fromJson(const QJsonObject &jsonObject) UAVObject *object = getObject(jObject["name"].toString(), jObject["instance"].toInt()); if (object != NULL) { object->fromJson(jObject); + if (updatedObjects != NULL) { + updatedObjects->append(object); + } } } } diff --git a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.h b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.h index cc6460abe..c65e54e71 100644 --- a/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.h +++ b/ground/openpilotgcs/src/plugins/uavobjects/uavobjectmanager.h @@ -59,7 +59,7 @@ public: void toJson(QJsonObject &jsonObject, JSON_EXPORT_OPTION what = JSON_EXPORT_ALL); void toJson(QJsonObject &jsonObject, const QList &objectsToExport); void toJson(QJsonObject &jsonObject, const QList &objectsToExport); - void fromJson(const QJsonObject &jsonObject); + void fromJson(const QJsonObject &jsonObject, QList *updatedObjects = NULL); signals: void newObject(UAVObject *obj); From 8d76e6f6715c3dacc9fba8deac1597f3da2619f5 Mon Sep 17 00:00:00 2001 From: m_thread Date: Thu, 25 Sep 2014 23:19:50 +0200 Subject: [PATCH 182/203] OP-1222 Uncrustified code. --- .../setupwizard/pages/airframeinitialtuningpage.cpp | 2 ++ .../plugins/setupwizard/vehicleconfigurationhelper.cpp | 9 +++++---- 2 files changed, 7 insertions(+), 4 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp index d3383f07c..a8fcb3dca 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/airframeinitialtuningpage.cpp @@ -162,6 +162,7 @@ void AirframeInitialTuningPage::loadValidFiles() QStringList files = templateDir.entryList(); foreach(QString fileName, files) { QFile file(QString("%1/%2").arg(templateDir.absolutePath()).arg(fileName)); + if (file.open(QFile::ReadOnly)) { QByteArray jsonData = file.readAll(); QJsonDocument templateDoc = QJsonDocument::fromJson(jsonData); @@ -185,6 +186,7 @@ void AirframeInitialTuningPage::setupTemplateList() item->setData(Qt::UserRole + 1, QVariant::fromValue((QJsonObject *)NULL)); foreach(QString templ, m_templates.keys()) { QJsonObject *json = m_templates[templ]; + item = new QListWidgetItem(json->value("name").toString(), ui->templateList); item->setData(Qt::UserRole + 1, QVariant::fromValue(json)); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 2cfa8df32..f8e7c29a7 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -753,11 +753,12 @@ void VehicleConfigurationHelper::applyManualControlDefaults() void VehicleConfigurationHelper::applyTemplateSettings() { if (m_configSource->getVehicleTemplate() != NULL) { - QJsonObject* json = m_configSource->getVehicleTemplate(); - QList updatedObjects; + QJsonObject *json = m_configSource->getVehicleTemplate(); + QList updatedObjects; m_uavoManager->fromJson(*json, &updatedObjects); - foreach (UAVObject* object, updatedObjects) { - UAVDataObject *dataObj = dynamic_cast(object); + foreach(UAVObject * object, updatedObjects) { + UAVDataObject *dataObj = dynamic_cast(object); + if (dataObj != NULL) { addModifiedObject(dataObj, QString(tr("Writing template settings for %1")).arg(object->getName())); } From 045757a6bb52c1d7b834a66b0a6f42b0b4cff581 Mon Sep 17 00:00:00 2001 From: Fredrik Larsson Date: Fri, 26 Sep 2014 08:47:42 +1000 Subject: [PATCH 183/203] Back to 2K --- shared/uavobjectdefinition/mpu6000settings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/mpu6000settings.xml b/shared/uavobjectdefinition/mpu6000settings.xml index 59d469c78..943243fa7 100644 --- a/shared/uavobjectdefinition/mpu6000settings.xml +++ b/shared/uavobjectdefinition/mpu6000settings.xml @@ -1,7 +1,7 @@ Settings for the @ref MPU6000 sensor used on CC3D and Revolution. Reboot the board for this to takes effect - + From 5da07fecea1e78395689b66f29247d83d88cee0e Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sat, 27 Sep 2014 17:16:30 +1000 Subject: [PATCH 184/203] Testing layout --- .../src/plugins/config/stabilization.ui | 9088 ++++++++--------- 1 file changed, 4544 insertions(+), 4544 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 852d16d35..7d19cfcbc 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -6,7 +6,7 @@ 0 0 - 882 + 995 789 @@ -95,7 +95,7 @@ QTabWidget::Rounded - 0 + 1 false @@ -136,8 +136,8 @@ 0 0 - 844 - 726 + 971 + 712 @@ -7836,9 +7836,9 @@ border-radius: 5; 0 - -295 - 844 - 998 + 0 + 954 + 742 @@ -7864,2864 +7864,4673 @@ border-radius: 5; - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Responsiveness - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - false - - - false - - - - 9 - - - 9 - - - 9 - - - 9 - - - 6 - - - - - false + + + + + true + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Responsiveness + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + false + + + false + + + + 9 - - - 0 - 0 - + + 9 - - - 0 - 140 - + + 9 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 251 - 251 - 251 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 255 - 255 - 255 - - - - - - - 251 - 251 - 251 - - - - - - - 124 - 124 - 124 - - - - - - - 165 - 165 - 165 - - - - - - - 124 - 124 - 124 - - - - - - - 255 - 255 - 255 - - - - - - - 124 - 124 - 124 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 0 - 0 - 0 - - - - - - - 248 - 248 - 248 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - + + 9 - - false + + 6 - - QGroupBox{border: 0px;} - - - - - - true - - - - 0 - - - 0 - - - 0 - - - 0 - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - + + + + false + + + + 0 + 0 + + + + + 0 + 140 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 251 + 251 + 251 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 255 + 255 + 255 + + + + + + + 251 + 251 + 251 + + + + + + + 124 + 124 + 124 + + + + + + + 165 + 165 + 165 + + + + + + + 124 + 124 + 124 + + + + + + + 255 + 255 + 255 + + + + + + + 124 + 124 + 124 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 0 + 0 + 0 + + + + + + + 248 + 248 + 248 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + false + + + QGroupBox{border: 0px;} + + + + + + true + + + 0 - - 180.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:PitchMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 128 - 16 - - - - - 16777215 - 16777215 - - - - - - - Max rate limit (all modes) (deg/s) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - + 0 - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:MaximumRate - element:Roll - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - + 0 - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:ManualRate - element:Yaw - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - + 0 - - 180.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:YawMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:MaximumRate - element:Pitch - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 20 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 180.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:PitchMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 128 + 16 + + + + + 16777215 + 16777215 + + + + + + + Max rate limit (all modes) (deg/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:MaximumRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:ManualRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 180.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:YawMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:MaximumRate + element:Pitch + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 20 + + + + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 36 - 36 - 36 + 58 + 58 + 58 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 48 + 48 + 48 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 26 + 26 + 26 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 74 - 74 - 74 + 0 + 0 + 0 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 220 - - + + + + - 36 - 36 - 36 + 0 + 0 + 0 - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 36 - 36 - 36 + 58 + 58 + 58 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 48 + 48 + 48 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 26 + 26 + 26 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 20 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + Yaw + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 20 + + + + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 36 - 36 - 36 + 58 + 58 + 58 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 48 + 48 + 48 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 26 + 26 + 26 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 74 - 74 - 74 + 0 + 0 + 0 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 220 - - + + + + - 36 - 36 - 36 + 0 + 0 + 0 - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 36 - 36 - 36 + 58 + 58 + 58 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 48 + 48 + 48 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 26 + 26 + 26 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Attitude mode response (deg) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:ManualRate - element:Pitch - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 140 - 16 - - - - - - - - - 0 - 0 - - - - - 0 - 20 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + Pitch + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 69 + 16 + + + + + + + Attitude mode response (deg) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:ManualRate + element:Pitch + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 140 + 16 + + + + + + + + + 0 + 0 + + + + + 0 + 20 + + + + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 36 - 36 - 36 + 58 + 58 + 58 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 48 + 48 + 48 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 26 + 26 + 26 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 74 - 74 - 74 + 0 + 0 + 0 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 255 + 255 + 220 - - + + + + - 36 - 36 - 36 + 0 + 0 + 0 - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - + + + + + + - 74 - 74 - 74 + 255 + 255 + 255 - - + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + - 36 - 36 - 36 + 58 + 58 + 58 - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - + + + + - 74 - 74 - 74 + 48 + 48 + 48 - - + + + + - 36 - 36 - 36 + 19 + 19 + 19 - - - - - - - - + + + + - 74 - 74 - 74 + 26 + 26 + 26 - - + + + + - 36 - 36 - 36 + 255 + 255 + 255 - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); color: rgb(255, 255, 255); border-radius: 5; - - - Roll - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - + + + Roll + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:ManualRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + QAbstractSpinBox::UpDownArrows + + + 0 + + + 180.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:RollMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:MaximumRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 16 + + + + + + + Rate mode response (deg/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + + Qt::Horizontal + + + + 20 + 20 + + + + + + + + + + + + 0 + 0 + + + + Use Advanced Configuration + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:6 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + + + + + + + + + 0 + 0 + + + + Thrust PID Scaling + + + false + + + + + + + 0 + 0 + + + + + 200 + 200 + + + + + 7 + + + + + + + + QFrame::NoFrame + + + QFrame::Raised + + + 0 - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:ManualRate - element:Roll - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - QAbstractSpinBox::UpDownArrows - - + 0 - - 180.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:RollMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - + 0 - - 1000000.000000000000000 + + 0 - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:MaximumRate - element:Yaw - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 16 - - - - - - - Rate mode response (deg/s) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - Qt::Horizontal - - - - 20 - 20 - - - - - - - - - - - - 0 - 0 - - - - Use Advanced Configuration - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:6 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - - - + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:99 + + + + + + + + + + + Qt::Horizontal + + + QSizePolicy::Expanding + + + + 40 + 20 + + + + + + + + QFrame::NoFrame + + + QFrame::Raised + + + + + + Enable Thrust PID Scaling + + + + objname:StabilizationSettingsBankX + fieldname:EnableThrustPIDScaling + buttongroup:99 + + + + + + + + + 0 + 0 + + + + + 0 + 20 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Source + + + Qt::AlignCenter + + + + + + + + objname:StabilizationSettingsBankX + fieldname:ThrustPIDScaleSource + buttongroup:99 + + + + + + + + + 0 + 0 + + + + + 0 + 20 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Targets + + + Qt::AlignCenter + + + + + + + + objname:StabilizationSettingsBankX + fieldname:ThrustPIDScaleTarget + buttongroup:99 + + + + + + + + + 0 + 0 + + + + + 0 + 20 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Axis + + + Qt::AlignCenter + + + + + + + + objname:StabilizationSettingsBankX + fieldname:ThrustPIDScaleAxes + buttongroup:99 + + + + + + + + + + + @@ -16182,1815 +17991,6 @@ border-radius: 5; - - - - Thrust PID Scaling - - - false - - - - - - - 0 - 0 - - - - - 200 - 200 - - - - - 7 - - - - - - - - QFrame::NoFrame - - - QFrame::Raised - - - - 0 - - - 0 - - - 0 - - - 0 - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:99 - - - - - - - - - - - Qt::Horizontal - - - QSizePolicy::Expanding - - - - 40 - 20 - - - - - - - - QFrame::NoFrame - - - QFrame::Raised - - - - - - Enable Thrust PID Scaling - - - - objname:StabilizationSettingsBankX - fieldname:EnableThrustPIDScaling - buttongroup:99 - - - - - - - - - 0 - 0 - - - - - 0 - 20 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Source - - - Qt::AlignCenter - - - - - - - - objname:StabilizationSettingsBankX - fieldname:ThrustPIDScaleSource - buttongroup:99 - - - - - - - - - 0 - 0 - - - - - 0 - 20 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Targets - - - Qt::AlignCenter - - - - - - - - objname:StabilizationSettingsBankX - fieldname:ThrustPIDScaleTarget - buttongroup:99 - - - - - - - - - 0 - 0 - - - - - 0 - 20 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Axis - - - Qt::AlignCenter - - - - - - - - objname:StabilizationSettingsBankX - fieldname:ThrustPIDScaleAxes - buttongroup:99 - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - @@ -18108,8 +18108,8 @@ border-radius: 5; 0 0 - 860 - 703 + 971 + 712 @@ -24051,8 +24051,8 @@ font:bold; 0 0 - 860 - 703 + 971 + 712 From 6cb6d32f790bb190b6eebd39e1d42006c746cdfc Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sat, 27 Sep 2014 18:08:20 +1000 Subject: [PATCH 185/203] More tinkering, m_thread what do you think? --- .../src/plugins/config/stabilization.ui | 265 ++++++++---------- 1 file changed, 123 insertions(+), 142 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 7d19cfcbc..4ecfb4084 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -7838,7 +7838,7 @@ border-radius: 5; 0 0 954 - 742 + 750 @@ -7864,7 +7864,7 @@ border-radius: 5; - + @@ -7916,6 +7916,70 @@ border-radius: 5; 6 + + + + + 0 + 0 + + + + Use Advanced Configuration + + + + + + + + 0 + 0 + + + + + 0 + 0 + + + + + 16777215 + 16777215 + + + + Reset all values to GCS defaults + + + + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:6 + + + + + + + + Qt::Horizontal + + + + 40 + 20 + + + + @@ -10661,70 +10725,6 @@ border-radius: 5; - - - - - 0 - 0 - - - - Use Advanced Configuration - - - - - - - - 0 - 0 - - - - - 0 - 0 - - - - - 16777215 - 16777215 - - - - Reset all values to GCS defaults - - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:6 - - - - - - - - Qt::Horizontal - - - - 40 - 20 - - - - @@ -10736,90 +10736,27 @@ border-radius: 5; 0 + + + 16777215 + 16777215 + + Thrust PID Scaling false - - - - - - 0 - 0 - - + + + - 200 - 200 + 140 + 0 - - - 7 - - - - - - - - QFrame::NoFrame - - - QFrame::Raised - - - - 0 - - - 0 - - - 0 - - - 0 - - - - - Default - - - - objname:StabilizationSettings - button:default - buttongroup:99 - - - - - - - - - - - Qt::Horizontal - - - QSizePolicy::Expanding - - - - 40 - 20 - - - - - - QFrame::NoFrame @@ -10830,7 +10767,7 @@ border-radius: 5; - Enable Thrust PID Scaling + Enable TPS @@ -12524,9 +12461,53 @@ border-radius: 5; + + + + + 0 + 0 + + + + Qt::LeftToRight + + + Default + + + + objname:StabilizationSettings + button:default + buttongroup:99 + + + + + + + + + 0 + 0 + + + + + 180 + 180 + + + + + 7 + + + + @@ -26928,7 +26909,7 @@ border-radius: 5; - + :/core/images/helpicon.svg:/core/images/helpicon.svg From 005b0feec1b5ef8734baa1c1c8908b9f4842a72e Mon Sep 17 00:00:00 2001 From: Alessio Morale Date: Sat, 27 Sep 2014 11:11:51 +0200 Subject: [PATCH 186/203] Change Revo Main port default to disabled as telemetry causes issues with OPlink --- shared/uavobjectdefinition/hwsettings.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/hwsettings.xml b/shared/uavobjectdefinition/hwsettings.xml index 0f24744a4..09b79d388 100644 --- a/shared/uavobjectdefinition/hwsettings.xml +++ b/shared/uavobjectdefinition/hwsettings.xml @@ -13,7 +13,7 @@ - + From 18b35e858fce6b23b86ba4f02c8ac81cb5039e84 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Sat, 27 Sep 2014 21:39:25 +1000 Subject: [PATCH 187/203] Mac stuff --- make/tools.mk | 36 ++++++++++++++++++------------------ 1 file changed, 18 insertions(+), 18 deletions(-) diff --git a/make/tools.mk b/make/tools.mk index 86ff73da8..3a2834c80 100644 --- a/make/tools.mk +++ b/make/tools.mk @@ -61,14 +61,14 @@ ifeq ($(UNAME), Linux) ifeq ($(ARCH), x86_64) ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-linux.tar.bz2 ARM_SDK_MD5_URL:= https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-linux.tar.bz2/+md5 - QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-linux-x64-5.3.1.run - QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-linux-x64-5.3.1.run.md5 + QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.2/qt-opensource-linux-x64-5.3.2.run + QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.2/qt-opensource-linux-x64-5.3.2.run.md5 QT_SDK_ARCH := gcc_64 else ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-linux.tar.bz2 ARM_SDK_MD5_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-linux.tar.bz2/+md5 - QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-linux-x86-5.3.1.run - QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-linux-x86-5.3.1.run.md5 + QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.2/qt-opensource-linux-x86-5.3.2.run + QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.2/qt-opensource-linux-x86-5.3.2.run.md5 QT_SDK_ARCH := gcc endif UNCRUSTIFY_URL := http://wiki.openpilot.org/download/attachments/18612236/uncrustify-0.60.tar.gz @@ -76,7 +76,7 @@ ifeq ($(UNAME), Linux) else ifeq ($(UNAME), Darwin) ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-mac.tar.bz2 ARM_SDK_MD5_URL:= https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-mac.tar.bz2/+md5 - QT_SDK_URL := http://qtmirror.ics.com/pub/qtproject/archive/qt/5.3/5.3.2/qt-opensource-mac-x64-clang-5.3.2.dmg + QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.2/qt-opensource-mac-x64-clang-5.3.2.dmg QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.2/qt-opensource-mac-x64-clang-5.3.2.dmg.md5 QT_SDK_ARCH := clang_64 QT_SDK_MAINTENANCE_TOOL := /Volumes/qt-opensource-mac-x64-clang-5.3.2/qt-opensource-mac-x64-clang-5.3.2.app/Contents/MacOS/qt-opensource-mac-x64-clang-5.3.2 @@ -87,8 +87,8 @@ else ifeq ($(UNAME), Darwin) else ifeq ($(UNAME), Windows) ARM_SDK_URL := https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-win32.zip ARM_SDK_MD5_URL:= https://launchpad.net/gcc-arm-embedded/4.8/4.8-2014-q1-update/+download/gcc-arm-none-eabi-4_8-2014q1-20140314-win32.zip/+md5 - QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-windows-x86-mingw482_opengl-5.3.1.exe - QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.1/qt-opensource-windows-x86-mingw482_opengl-5.3.1.exe.md5 + QT_SDK_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.2/qt-opensource-windows-x86-mingw482_opengl-5.3.2.exe + QT_SDK_MD5_URL := http://download.qt-project.org/official_releases/qt/5.3/5.3.2/qt-opensource-windows-x86-mingw482_opengl-5.3.2.exe.md5 QT_SDK_ARCH := mingw482_32 NSIS_URL := http://wiki.openpilot.org/download/attachments/18612236/nsis-2.46-unicode.tar.bz2 SDL_URL := http://wiki.openpilot.org/download/attachments/18612236/SDL-devel-1.2.15-mingw32.tar.gz @@ -368,12 +368,12 @@ qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR) # Extract packages under tool directory $(V1) $(MKDIR) -p $$(call toprel, $(dir $(2))) $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0qt-project-url.7z" | grep -v Extracting - $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/5.3.1ThirdPartySoftware_Listing.7z" | grep -v Extracting + $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/5.3.2ThirdPartySoftware_Listing.7z" | grep -v Extracting $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0readme.7z" | grep -v Extracting - $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.win32_mingw482/5.3.1-0qt5_essentials.7z" | grep -v Extracting - $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.win32_mingw482/5.3.1-0i686-4.8.2-release-posix-dwarf-rt_v3-rev3-runtime.7z" | grep -v Extracting - $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.win32_mingw482/5.3.1-0icu_52_1_mingw_builds_32_4_8_2_posix_dwarf.7z" | grep -v Extracting - $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.win32_mingw482/5.3.1-0qt5_addons.7z" | grep -v Extracting + $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.win32_mingw482/5.3.2-0qt5_essentials.7z" | grep -v Extracting + $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.win32_mingw482/5.3.2-0i686-4.8.2-release-posix-dwarf-rt_v3-rev3-runtime.7z" | grep -v Extracting + $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.win32_mingw482/5.3.2-0icu_52_1_mingw_builds_32_4_8_2_posix_dwarf.7z" | grep -v Extracting + $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.win32_mingw482/5.3.2-0qt5_addons.7z" | grep -v Extracting $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.tools.win32_mingw482/4.8.2i686-4.8.2-release-posix-dwarf-rt_v3-rev3.7z" | grep -v Extracting # Run patcher @$(ECHO) @@ -435,13 +435,13 @@ qt_sdk_install: qt_sdk_clean | $(DL_DIR) $(TOOLS_DIR) # Extract packages under tool directory $(V1) $(MKDIR) -p $$(call toprel, $(dir $(2))) $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0qt-project-url.7z" | grep -v Extracting - $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/5.3.1ThirdPartySoftware_Listing.7z" | grep -v Extracting + $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt/5.3.2ThirdPartySoftware_Listing.7z" | grep -v Extracting $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.readme/1.0.0-0readme.7z" | grep -v Extracting - $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0qt5_essentials.7z" | grep -v Extracting - $(V1) if [ -f "$(1)/qt.53.$(6)/5.3.1-0icu_52_1_ubuntu_11_10_64.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0icu_52_1_ubuntu_11_10_64.7z" | grep -v Extracting; fi - $(V1) if [ -f "$(1)/qt.53.$(6)/5.3.1-0icu_52_1_ubuntu_11_10_32.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0icu_52_1_ubuntu_11_10_32.7z" | grep -v Extracting; fi - $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.1-0qt5_addons.7z" | grep -v Extracting -# go to OpenPilot/tools/5.3.1/gcc_64 and call patcher.sh + $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.2-0qt5_essentials.7z" | grep -v Extracting + $(V1) if [ -f "$(1)/qt.53.$(6)/5.3.2-0icu_52_1_ubuntu_11_10_64.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.2-0icu_52_1_ubuntu_11_10_64.7z" | grep -v Extracting; fi + $(V1) if [ -f "$(1)/qt.53.$(6)/5.3.2-0icu_52_1_ubuntu_11_10_32.7z" ]; then $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.2-0icu_52_1_ubuntu_11_10_32.7z" | grep -v Extracting; fi + $(V1) $(SEVENZIP) -y -o$(2) x "$(1)/qt.53.$(6)/5.3.2-0qt5_addons.7z" | grep -v Extracting +# go to OpenPilot/tools/5.3.2/gcc_64 and call patcher.sh @$(ECHO) @$(ECHO) "Running patcher in" $$(call toprel, $(QT_SDK_PREFIX)) $(V1) $(CD) $(QT_SDK_PREFIX) From 11822fa0a960ff93646699df4b18f0c2201ea797 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sat, 27 Sep 2014 14:26:01 +0200 Subject: [PATCH 188/203] OP-1222 Fixed stab layout. --- .../src/plugins/config/stabilization.ui | 2998 ++++++++--------- 1 file changed, 1482 insertions(+), 1516 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/stabilization.ui b/ground/openpilotgcs/src/plugins/config/stabilization.ui index 4ecfb4084..f8a4a86b4 100644 --- a/ground/openpilotgcs/src/plugins/config/stabilization.ui +++ b/ground/openpilotgcs/src/plugins/config/stabilization.ui @@ -95,7 +95,7 @@ QTabWidget::Rounded - 1 + 0 false @@ -7838,7 +7838,7 @@ border-radius: 5; 0 0 954 - 750 + 732 @@ -7916,7 +7916,7 @@ border-radius: 5; 6 - + @@ -7929,7 +7929,20 @@ border-radius: 5; - + + + + Qt::Horizontal + + + + 40 + 20 + + + + + @@ -7967,19 +7980,6 @@ border-radius: 5; - - - - Qt::Horizontal - - - - 40 - 20 - - - - @@ -8424,10 +8424,13 @@ border-radius: 5; true - + 0 + + 0 + 0 @@ -8437,1473 +8440,6 @@ border-radius: 5; 0 - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 180.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:PitchMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 128 - 16 - - - - - 16777215 - 16777215 - - - - - - - Max rate limit (all modes) (deg/s) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:MaximumRate - element:Roll - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:ManualRate - element:Yaw - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 180.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:YawMax - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 22 - - - - - 16777215 - 22 - - - - Qt::StrongFocus - - - <html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html> - - - - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - 0 - - - 1000000.000000000000000 - - - 1.000000000000000 - - - - objname:StabilizationSettingsBankX - fieldname:MaximumRate - element:Pitch - haslimits:no - scale:1 - buttongroup:6,20 - - - - - - - - - 0 - 0 - - - - - 0 - 20 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Yaw - - - Qt::AlignCenter - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 10 - 10 - - - - - - - - - 0 - 0 - - - - - 0 - 20 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 19 - 19 - 19 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 58 - 58 - 58 - - - - - - - 48 - 48 - 48 - - - - - - - 19 - 19 - 19 - - - - - - - 26 - 26 - 26 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - 255 - 255 - 255 - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - - - 74 - 74 - 74 - - - - - 36 - 36 - 36 - - - - - - - - - 0 - 0 - 0 - - - - - - - 39 - 39 - 39 - - - - - - - 255 - 255 - 220 - - - - - - - 0 - 0 - 0 - - - - - - - - - 75 - true - - - - false - - - background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); -color: rgb(255, 255, 255); -border-radius: 5; - - - Pitch - - - Qt::AlignCenter - - - - - - - - 0 - 0 - - - - - 69 - 16 - - - - - - - Attitude mode response (deg) - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - @@ -9957,22 +8493,6 @@ border-radius: 5; - - - - Qt::Horizontal - - - QSizePolicy::Fixed - - - - 140 - 16 - - - - @@ -10631,6 +9151,20 @@ border-radius: 5; + + + + + + + Rate mode +response (deg/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + @@ -10684,10 +9218,10 @@ border-radius: 5; - - + + - + 0 0 @@ -10695,36 +9229,1450 @@ border-radius: 5; 0 - 16 + 22 + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html> + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:MaximumRate + element:Roll + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the degrees per second that your vehicle will tilt/rotate at full stick input when in all modes except Attitude.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:ManualRate + element:Yaw + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 180.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:YawMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 20 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + - Rate mode response (deg/s) + Pitch + + + Qt::AlignCenter + + + + + + + Qt::Horizontal + + + QSizePolicy::Fixed + + + + 10 + 10 + + + + + + + + + 0 + 0 + + + + + 0 + 22 + + + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the maximum rotation rate in degrees per second on an axis.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 1000000.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:MaximumRate + element:Pitch + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + 0 + 0 + + + + + 0 + 20 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 19 + 19 + 19 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 58 + 58 + 58 + + + + + + + 48 + 48 + 48 + + + + + + + 19 + 19 + 19 + + + + + + + 26 + 26 + 26 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + 255 + 255 + 255 + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + + + 74 + 74 + 74 + + + + + 36 + 36 + 36 + + + + + + + + + 0 + 0 + 0 + + + + + + + 39 + 39 + 39 + + + + + + + 255 + 255 + 220 + + + + + + + 0 + 0 + 0 + + + + + + + + + 75 + true + + + + false + + + background-color: qlineargradient(spread:reflect, x1:0.507, y1:0, x2:0.507, y2:0.772, stop:0.208955 rgba(74, 74, 74, 255), stop:0.78607 rgba(36, 36, 36, 255)); +color: rgb(255, 255, 255); +border-radius: 5; + + + Yaw + + + Qt::AlignCenter + + + + + + + + + + Attitude mode +response (deg) Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - Qt::Horizontal + + + + + 0 + 0 + - + - 20 - 20 + 0 + 22 - + + + 16777215 + 22 + + + + Qt::StrongFocus + + + <html><head/><body><p>This sets the maximum deg your vehicle will tilt at full stick input when in Attitude mode.</p></body></html> + + + + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + 0 + + + 180.000000000000000 + + + 1.000000000000000 + + + + objname:StabilizationSettingsBankX + fieldname:PitchMax + haslimits:no + scale:1 + buttongroup:6,20 + + + + + + + + + + + Max rate limit +(all modes) (deg/s) + + + Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter + + + + + + Qt::Vertical + + + + 20 + 40 + + + + @@ -10748,7 +10696,13 @@ border-radius: 5; false - + + + 9 + + + 9 + @@ -10764,6 +10718,18 @@ border-radius: 5; QFrame::Raised + + 0 + + + 0 + + + 0 + + + 0 + @@ -26909,7 +26875,7 @@ border-radius: 5; - + :/core/images/helpicon.svg:/core/images/helpicon.svg From 3d20e201af2fb3af70d81b1216af1b929e1e08fb Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Sat, 27 Sep 2014 15:49:53 +0200 Subject: [PATCH 189/203] OP-1222 Fixed 'default' values for TPS curve when no board is connected. --- .../src/plugins/config/configstabilizationwidget.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 9fc95ca3e..3b02f285c 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -133,6 +133,7 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa ui->thrustPIDScalingCurve->setYAxisLabel(tr("Scaling factor")); ui->thrustPIDScalingCurve->setMin(-0.5); ui->thrustPIDScalingCurve->setMax(0.5); + ui->thrustPIDScalingCurve->initLinearCurve(5, -0.25, 0.25); addWidget(ui->defaultThrottleCurveButton); addWidget(ui->enableThrustPIDScalingCheckBox); From 012c1ae940406e969d07dd2384de9ee58212c122 Mon Sep 17 00:00:00 2001 From: m_thread Date: Sun, 28 Sep 2014 01:04:47 +0200 Subject: [PATCH 190/203] OP-1222 Fixed a merge accident. Some cleanup. --- .../configfixedwingwidget.cpp | 47 ++++++++++++++++--- .../cfg_vehicletypes/configfixedwingwidget.h | 3 ++ .../configmultirotorwidget.cpp | 2 - 3 files changed, 43 insertions(+), 9 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp index 42118be0b..45f381bac 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.cpp @@ -84,12 +84,15 @@ ConfigFixedWingWidget::ConfigFixedWingWidget(QWidget *parent) : populateChannelComboBoxes(); QStringList fixedWingTypes; - fixedWingTypes << "Elevator aileron rudder" << "Elevon" << "Vtail"; + fixedWingTypes << "Aileron" << "Elevon" << "Vtail"; m_aircraft->fixedWingType->addItems(fixedWingTypes); - // Set default model to "Elevator aileron rudder" + m_aircraft->planeShape->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + m_aircraft->planeShape->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + + // Set default model to "Aileron" connect(m_aircraft->fixedWingType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); - m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Elevator aileron rudder")); + m_aircraft->fixedWingType->setCurrentIndex(m_aircraft->fixedWingType->findText("Aileron")); setupUI(m_aircraft->fixedWingType->currentText()); } @@ -104,9 +107,14 @@ ConfigFixedWingWidget::~ConfigFixedWingWidget() void ConfigFixedWingWidget::setupUI(QString frameType) { Q_ASSERT(m_aircraft); + QSvgRenderer *renderer = new QSvgRenderer(); + renderer->load(QString(":/configgadget/images/fixedwing-shapes.svg")); + planeimg = new QGraphicsSvgItem(); + planeimg->setSharedRenderer(renderer); - if (frameType == "FixedWing" || frameType == "Elevator aileron rudder") { - setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevator aileron rudder")); + if (frameType == "FixedWing" || frameType == "Aileron") { + planeimg->setElementId("aileron"); + setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Aileron")); m_aircraft->fwRudder1ChannelBox->setEnabled(true); m_aircraft->fwRudder2ChannelBox->setEnabled(true); m_aircraft->fwElevator1ChannelBox->setEnabled(true); @@ -122,14 +130,16 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->elevonSlider1->setEnabled(false); m_aircraft->elevonSlider2->setEnabled(false); } else if (frameType == "FixedWingElevon" || frameType == "Elevon") { + planeimg->setElementId("elevon"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Elevon")); m_aircraft->fwAileron1Label->setText("Elevon 1"); m_aircraft->fwAileron2Label->setText("Elevon 2"); m_aircraft->fwElevator1ChannelBox->setEnabled(false); m_aircraft->fwElevator2ChannelBox->setEnabled(false); m_aircraft->fwRudder1ChannelBox->setEnabled(true); + m_aircraft->fwElevator1ChannelBox->setCurrentText("None"); m_aircraft->fwRudder2ChannelBox->setEnabled(true); - + m_aircraft->fwElevator2ChannelBox->setCurrentText("None"); m_aircraft->fwElevator1Label->setText("Elevator 1"); m_aircraft->fwElevator2Label->setText("Elevator 2"); m_aircraft->elevonLabel1->setText("Roll"); @@ -138,9 +148,12 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->elevonSlider1->setEnabled(true); m_aircraft->elevonSlider2->setEnabled(true); } else if (frameType == "FixedWingVtail" || frameType == "Vtail") { + planeimg->setElementId("vtail"); setComboCurrentIndex(m_aircraft->fixedWingType, m_aircraft->fixedWingType->findText("Vtail")); m_aircraft->fwRudder1ChannelBox->setEnabled(false); + m_aircraft->fwRudder1ChannelBox->setCurrentText("None"); m_aircraft->fwRudder2ChannelBox->setEnabled(false); + m_aircraft->fwRudder2ChannelBox->setCurrentText("None"); m_aircraft->fwElevator1Label->setText("Vtail 1"); m_aircraft->fwElevator1ChannelBox->setEnabled(true); @@ -156,6 +169,11 @@ void ConfigFixedWingWidget::setupUI(QString frameType) m_aircraft->elevonSlider1->setEnabled(true); m_aircraft->elevonSlider2->setEnabled(true); } + QGraphicsScene *scene = new QGraphicsScene(); + scene->addItem(planeimg); + scene->setSceneRect(planeimg->boundingRect()); + m_aircraft->planeShape->fitInView(planeimg, Qt::KeepAspectRatio); + m_aircraft->planeShape->setScene(scene); } void ConfigFixedWingWidget::registerWidgets(ConfigTaskWidget &parent) @@ -264,7 +282,7 @@ QString ConfigFixedWingWidget::updateConfigObjectsFromWidgets() setThrottleCurve(mixer, VehicleConfig::MIXER_THROTTLECURVE1, m_aircraft->fixedWingThrottle->getCurve()); // All airframe types must start with "FixedWing" - if (m_aircraft->fixedWingType->currentText() == "Elevator aileron rudder") { + if (m_aircraft->fixedWingType->currentText() == "Aileron") { airframeType = "FixedWing"; setupFrameFixedWing(airframeType); } else if (m_aircraft->fixedWingType->currentText() == "Elevon") { @@ -600,3 +618,18 @@ bool ConfigFixedWingWidget::throwConfigError(QString airframeType) return error; } + + +void ConfigFixedWingWidget::resizeEvent(QResizeEvent *) +{ + if (planeimg) { + m_aircraft->planeShape->fitInView(planeimg, Qt::KeepAspectRatio); + } +} + +void ConfigFixedWingWidget::showEvent(QShowEvent *) +{ + if (planeimg) { + m_aircraft->planeShape->fitInView(planeimg, Qt::KeepAspectRatio); + } +} diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index 7f9ad7891..1821190c0 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -65,10 +65,13 @@ private: protected: void enableControls(bool enable); + void resizeEvent(QResizeEvent *); + void showEvent(QShowEvent *); private slots: virtual void setupUI(QString airframeType); virtual bool throwConfigError(QString airframeType); + }; #endif // CONFIGFIXEDWINGWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp index a4684ba02..18b40471c 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configmultirotorwidget.cpp @@ -144,8 +144,6 @@ ConfigMultiRotorWidget::ConfigMultiRotorWidget(QWidget *parent) : // Set default model to "Quad X" m_aircraft->multirotorFrameType->setCurrentIndex(m_aircraft->multirotorFrameType->findText("Quad X")); - // setupUI(m_aircraft->multirotorFrameType->currentText()); - connect(m_aircraft->multirotorFrameType, SIGNAL(currentIndexChanged(QString)), this, SLOT(setupUI(QString))); // Connect the multirotor motor reverse checkbox From 7a00c7f90567ac2706d7041337de05b824b2bfd1 Mon Sep 17 00:00:00 2001 From: m_thread Date: Sun, 28 Sep 2014 02:00:54 +0200 Subject: [PATCH 191/203] OP-1222 Fixed false positive dirty indication for stabilization tab in configplugin. Added tracking of TPS curve changes. --- .../src/plugins/config/configstabilizationwidget.cpp | 10 ++++++++++ .../src/plugins/config/configstabilizationwidget.h | 2 +- .../plugins/uavobjectwidgetutils/configtaskwidget.h | 2 +- 3 files changed, 12 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index 3b02f285c..e8dbadbee 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -134,6 +134,7 @@ ConfigStabilizationWidget::ConfigStabilizationWidget(QWidget *parent) : ConfigTa ui->thrustPIDScalingCurve->setMin(-0.5); ui->thrustPIDScalingCurve->setMax(0.5); ui->thrustPIDScalingCurve->initLinearCurve(5, -0.25, 0.25); + connect(ui->thrustPIDScalingCurve, SIGNAL(curveUpdated()), this, SLOT(throttleCurveUpdated())); addWidget(ui->defaultThrottleCurveButton); addWidget(ui->enableThrustPIDScalingCheckBox); @@ -170,6 +171,7 @@ void ConfigStabilizationWidget::updateObjectsFromWidgets() void ConfigStabilizationWidget::updateThrottleCurveFromObject() { + bool dirty = isDirty(); UAVObject *stabBank = getObjectManager()->getObject(QString(m_pidTabBars.at(0)->tabData(m_currentPIDBank).toString())); Q_ASSERT(stabBank); @@ -192,6 +194,7 @@ void ConfigStabilizationWidget::updateThrottleCurveFromObject() bool enabled = field->getValue() == "TRUE"; ui->enableThrustPIDScalingCheckBox->setChecked(enabled); ui->thrustPIDScalingCurve->setEnabled(enabled); + setDirty(dirty); } void ConfigStabilizationWidget::updateObjectFromThrottleCurve() @@ -242,6 +245,11 @@ void ConfigStabilizationWidget::resetThrottleCurveToDefault() delete defaultStabBank; } +void ConfigStabilizationWidget::throttleCurveUpdated() +{ + setDirty(true); +} + void ConfigStabilizationWidget::realtimeUpdatesSlot(bool value) { ui->realTimeUpdates_6->setChecked(value); @@ -335,6 +343,7 @@ void ConfigStabilizationWidget::onBoardConnected() void ConfigStabilizationWidget::pidBankChanged(int index) { + bool dirty = isDirty(); updateObjectFromThrottleCurve(); foreach(QTabBar * tabBar, m_pidTabBars) { disconnect(tabBar, SIGNAL(currentChanged(int)), this, SLOT(pidBankChanged(int))); @@ -351,6 +360,7 @@ void ConfigStabilizationWidget::pidBankChanged(int index) m_currentPIDBank = index; qDebug() << "current bank:" << m_currentPIDBank; updateThrottleCurveFromObject(); + setDirty(dirty); } bool ConfigStabilizationWidget::shouldObjectBeSaved(UAVObject *object) diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h index 5b3c536f6..f8409c050 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.h @@ -74,6 +74,6 @@ private slots: void onBoardConnected(); void pidBankChanged(int index); void resetThrottleCurveToDefault(); + void throttleCurveUpdated(); }; - #endif // ConfigStabilizationWidget_H diff --git a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h index 6ff337060..3cf5c5253 100644 --- a/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h +++ b/ground/openpilotgcs/src/plugins/uavobjectwidgetutils/configtaskwidget.h @@ -139,7 +139,7 @@ public: void autoLoadWidgets(); bool isDirty(); - void setDirty(bool value); + virtual void setDirty(bool value); bool allObjectsUpdated(); void setOutOfLimitsStyle(QString style) From a0541f431c2b98198be86c1d4315d809a4460987 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Mon, 29 Sep 2014 21:12:37 +0200 Subject: [PATCH 192/203] OP-1222 Added vtail propeller --- .../config/images/fixedwing-shapes.svg | 246 ++++++++++-------- 1 file changed, 139 insertions(+), 107 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg index 9b5a425b0..952b65bee 100644 --- a/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg +++ b/ground/openpilotgcs/src/plugins/config/images/fixedwing-shapes.svg @@ -487,16 +487,20 @@ inkscape:window-height="928" id="namedview4099" showgrid="false" - inkscape:zoom="0.73144533" - inkscape:cx="784.15573" - inkscape:cy="958.96697" + inkscape:zoom="4.0911178" + inkscape:cx="396.11045" + inkscape:cy="611.35183" inkscape:window-x="0" inkscape:window-y="27" inkscape:window-maximized="1" - inkscape:current-layer="elevon" + inkscape:current-layer="Layer_1" showborder="true" inkscape:showpageshadow="false" - inkscape:object-paths="true" /> \ No newline at end of file + style="fill:none;stroke:#010101;stroke-width:0.69520003;stroke-linecap:round;stroke-linejoin:round" /> \ No newline at end of file From 87790711c24fdbf5fa6059fbe8541bb031fd32fe Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Mon, 29 Sep 2014 22:35:33 +0200 Subject: [PATCH 193/203] OP-1222 Updated wizard shapes with Vtail frame --- .../fixedwing-shapes-wizard-no-numbers.svg | 2415 ++++++++++++---- .../resources/fixedwing-shapes-wizard.svg | 2468 ++++++++++++++--- 2 files changed, 3998 insertions(+), 885 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg index 8f250956c..18656681f 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/fixedwing-shapes-wizard-no-numbers.svg @@ -14,9 +14,9 @@ id="Layer_1" x="0px" y="0px" - width="792" - height="2016" - viewBox="0 0 792 2016" + width="653.61542" + height="2094.717" + viewBox="0 0 653.61542 2094.717" enable-background="new 0 0 792 1008" xml:space="preserve" inkscape:version="0.48.5 r10040" @@ -258,22 +258,6 @@ x2="281.74301" y2="630.1615" />6 \ No newline at end of file + d="M 449.683,830.161 V 821.571 H 453.494 C 454.26,821.571 454.842,821.648 455.24,821.8 C 455.636,821.954 455.957,822.227 456.195,822.617 C 456.431,823.007 456.55,823.439 456.55,823.912 C 456.55,824.52 456.353,825.035 455.958,825.453 C 455.562,825.871 454.954,826.137 454.13,826.25 C 454.431,826.396 454.659,826.537 454.818,826.678 C 455.15,826.985 455.464,827.366 455.759,827.823 L 457.253,830.161 H 455.823 L 454.684,828.374 C 454.352,827.858 454.08,827.464 453.866,827.189 C 453.651,826.916 453.46,826.723 453.29,826.616 C 453.12,826.507 452.946,826.428 452.769,826.387 C 452.64,826.362 452.429,826.346 452.136,826.346 H 450.82 V 830.16 L 449.683,830.161 L 449.683,830.161 z M 450.819,825.362 H 453.26 C 453.781,825.362 454.186,825.306 454.481,825.201 C 454.774,825.094 454.997,824.922 455.149,824.683 C 455.299,824.448 455.378,824.192 455.378,823.912 C 455.378,823.506 455.232,823.172 454.937,822.91 C 454.642,822.647 454.175,822.515 453.541,822.515 H 450.822 L 450.819,825.362 L 450.819,825.362 z" + id="path4097-7" /> + + + +4 +6 + \ No newline at end of file From 1c7ab99e51ae2b7eb2338b55c438a9a2e7adf181 Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Mon, 29 Sep 2014 22:58:51 +0200 Subject: [PATCH 194/203] OP-1222 Updated connection-diagram with Vtail frame --- .../resources/connection-diagrams.svg | 1900 ++++++++++++++++- 1 file changed, 1877 insertions(+), 23 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg index fefc1c59a..4ba99d2fd 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -26,17 +26,17 @@ guidetolerance="10" inkscape:pageopacity="0" inkscape:pageshadow="2" - inkscape:window-width="593" - inkscape:window-height="439" + inkscape:window-width="1280" + inkscape:window-height="928" id="namedview4616" showgrid="false" - inkscape:zoom="0.1891554" - inkscape:cx="1013.827" - inkscape:cy="514.92134" - inkscape:window-x="331" - inkscape:window-y="337" - inkscape:window-maximized="0" - inkscape:current-layer="layer7" + inkscape:zoom="0.77062343" + inkscape:cx="919.09469" + inkscape:cy="317.10852" + inkscape:window-x="0" + inkscape:window-y="27" + inkscape:window-maximized="1" + inkscape:current-layer="g10948" fit-margin-top="15" fit-margin-left="15" fit-margin-right="15" @@ -48,7 +48,8 @@ inkscape:snap-bbox="true" inkscape:object-paths="true" inkscape:snap-bbox-midpoints="true" - inkscape:snap-bbox-edge-midpoints="true"> + inkscape:snap-bbox-edge-midpoints="true" + inkscape:object-nodes="true"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + @@ -28762,7 +29011,8 @@ id="layer13" inkscape:label="multirotors-frames" style="display:inline" - transform="translate(9.5291677,71.377308)"> + transform="translate(9.5291677,71.377308)" + sodipodi:insensitive="true"> + style="display:inline" + transform="translate(9.5291677,71.377308)"> + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + style="display:none" + sodipodi:insensitive="true"> + sodipodi:nodetypes="ccccccccccccccccccccccccccccccccccccccccccc" /> @@ -33744,6 +35574,29 @@ + + + + + + + @@ -33751,7 +35604,8 @@ inkscape:groupmode="layer" id="layer33" inkscape:label="fixed-wing-one-servo" - style="display:none"> + style="display:none" + sodipodi:insensitive="true"> @@ -34825,7 +36679,7 @@ d="M 411.435,717.672 C 411.435,719.19078 410.20378,720.422 408.685,720.422 C 407.16621,720.422 405.935,719.19078 405.935,717.672 C 405.935,716.15321 407.16621,714.922 408.685,714.922 C 410.20378,714.922 411.435,716.15321 411.435,717.672 z" /> @@ -34953,7 +36807,7 @@ d="M 216.804,613.62 C 216.804,615.13878 215.57278,616.37 214.054,616.37 C 212.53522,616.37 211.304,615.13878 211.304,613.62 C 211.304,612.10121 212.53522,610.87 214.054,610.87 C 215.57278,610.87 216.804,612.10121 216.804,613.62 z" /> From 4ab043fb653611f0a80253174ac5b45520533d4b Mon Sep 17 00:00:00 2001 From: Laurent Lalanne Date: Mon, 29 Sep 2014 23:56:09 +0200 Subject: [PATCH 195/203] OP-1222 Removed Tx wire for Sbus Rx (3 wires) - All wing frames heading top (follow revo red arrow) --- .../resources/connection-diagrams.svg | 3895 ++++++++--------- 1 file changed, 1944 insertions(+), 1951 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg index 4ba99d2fd..6e42f8ac6 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg +++ b/ground/openpilotgcs/src/plugins/setupwizard/resources/connection-diagrams.svg @@ -12,8 +12,8 @@ xmlns:sodipodi="http://sodipodi.sourceforge.net/DTD/sodipodi-0.dtd" xmlns:inkscape="http://www.inkscape.org/namespaces/inkscape" id="svg12651" - height="839.08447" - width="1309.343" + height="1074.8231" + width="1398.5884" version="1.1" inkscape:version="0.48.5 r10040" sodipodi:docname="connection-diagrams.svg"> @@ -30,13 +30,13 @@ inkscape:window-height="928" id="namedview4616" showgrid="false" - inkscape:zoom="0.77062343" - inkscape:cx="919.09469" - inkscape:cy="317.10852" + inkscape:zoom="0.67825113" + inkscape:cx="942.97766" + inkscape:cy="537.41156" inkscape:window-x="0" inkscape:window-y="27" inkscape:window-maximized="1" - inkscape:current-layer="g10948" + inkscape:current-layer="layer20" fit-margin-top="15" fit-margin-left="15" fit-margin-right="15" @@ -52,35 +52,35 @@ inkscape:object-nodes="true"> + originx="-32.46875px" + originy="239.45435px" /> @@ -104,7 +104,7 @@ @@ -118,7 +118,7 @@ @@ -145,7 +145,7 @@ style="overflow:visible"> @@ -159,7 +159,7 @@ style="overflow:visible"> @@ -181,7 +181,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10057"> @@ -189,7 +189,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10073"> @@ -221,7 +221,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10105"> @@ -250,7 +250,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10165"> @@ -258,7 +258,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10181"> @@ -274,7 +274,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10213"> @@ -290,7 +290,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10269"> @@ -298,7 +298,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10285"> @@ -314,7 +314,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10317"> @@ -330,7 +330,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4329"> @@ -338,7 +338,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4345"> @@ -354,7 +354,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4377"> @@ -386,7 +386,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4437"> @@ -394,7 +394,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4453"> @@ -410,7 +410,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4485"> @@ -434,7 +434,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4925"> @@ -442,7 +442,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4941"> @@ -458,7 +458,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4973"> @@ -487,7 +487,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7903"> @@ -495,7 +495,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7919"> @@ -511,7 +511,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7951"> @@ -540,7 +540,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5467"> @@ -548,7 +548,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5483"> @@ -556,7 +556,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5499"> @@ -564,7 +564,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5515"> @@ -572,7 +572,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5553"> @@ -588,7 +588,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5585"> @@ -604,7 +604,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5617"> @@ -620,7 +620,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5649"> @@ -636,7 +636,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5681"> @@ -652,7 +652,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5713"> @@ -668,7 +668,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5745"> @@ -684,7 +684,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5777"> @@ -713,7 +713,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7159"> @@ -721,7 +721,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7175"> @@ -737,7 +737,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7207"> @@ -753,7 +753,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7239"> @@ -761,7 +761,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7255"> @@ -777,7 +777,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7287"> @@ -793,7 +793,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7319"> @@ -801,7 +801,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7335"> @@ -817,7 +817,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7367"> @@ -833,7 +833,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7423"> @@ -841,7 +841,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7439"> @@ -857,7 +857,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7471"> @@ -873,7 +873,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7503"> @@ -881,7 +881,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7519"> @@ -897,7 +897,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7551"> @@ -913,7 +913,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7583"> @@ -921,7 +921,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7599"> @@ -937,7 +937,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7631"> @@ -966,7 +966,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5841"> @@ -974,7 +974,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5857"> @@ -982,7 +982,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5873"> @@ -990,7 +990,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5889"> @@ -998,7 +998,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5905"> @@ -1014,7 +1014,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5937"> @@ -1030,7 +1030,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5969"> @@ -1046,7 +1046,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6001"> @@ -1062,7 +1062,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6033"> @@ -1078,7 +1078,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6065"> @@ -1094,7 +1094,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6097"> @@ -1110,7 +1110,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6129"> @@ -1126,7 +1126,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6169"> @@ -1134,7 +1134,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6185"> @@ -1150,7 +1150,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6217"> @@ -1166,7 +1166,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6273"> @@ -1174,7 +1174,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6289"> @@ -1190,7 +1190,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6321"> @@ -1219,7 +1219,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5049"> @@ -1227,7 +1227,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5065"> @@ -1235,7 +1235,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5081"> @@ -1243,7 +1243,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5097"> @@ -1251,7 +1251,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5135"> @@ -1267,7 +1267,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5167"> @@ -1283,7 +1283,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5199"> @@ -1299,7 +1299,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5231"> @@ -1315,7 +1315,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5263"> @@ -1331,7 +1331,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5295"> @@ -1355,7 +1355,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5327"> @@ -1363,7 +1363,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5359"> @@ -1706,7 +1706,7 @@ @@ -1721,7 +1721,7 @@ inkscape:connector-curvature="0" id="path6056-4" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -1749,7 +1749,7 @@ inkscape:connector-curvature="0" id="path21212" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -1777,7 +1777,7 @@ inkscape:connector-curvature="0" id="path21220" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -1911,7 +1911,7 @@ inkscape:connector-curvature="0" id="path6056-7" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -1939,7 +1939,7 @@ inkscape:connector-curvature="0" id="path11149" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -1967,7 +1967,7 @@ inkscape:connector-curvature="0" id="path11157" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -2136,7 +2136,7 @@ inkscape:connector-curvature="0" id="path6056-0" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -2164,7 +2164,7 @@ inkscape:connector-curvature="0" id="path11726" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -2192,7 +2192,7 @@ inkscape:connector-curvature="0" id="path11734" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -2220,7 +2220,7 @@ inkscape:connector-curvature="0" id="path21220-7" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -2337,7 +2337,7 @@ inkscape:connector-curvature="0" id="path6056-77" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -2365,7 +2365,7 @@ inkscape:connector-curvature="0" id="path12589" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -2393,7 +2393,7 @@ inkscape:connector-curvature="0" id="path12597" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -2421,7 +2421,7 @@ inkscape:connector-curvature="0" id="path12605" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -2449,7 +2449,7 @@ inkscape:connector-curvature="0" id="path12613" style="fill-rule:evenodd;stroke-width:0.625;stroke-linejoin:round" - d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 c -1.7454984,2.3720609 -1.7354408,5.6174519 -6e-7,8.035443 z" + d="M 8.7185878,4.0337352 L -2.2072895,0.01601326 L 8.7185884,-4.0017078 C 6.97309,-1.6296469 6.9831476,1.6157441 8.7185878,4.0337352 z" transform="matrix(-0.3,0,0,-0.3,0.69,0)" /> @@ -2566,7 +2566,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10073-9"> @@ -2599,7 +2599,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10105-5"> @@ -2651,7 +2651,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10165-8"> @@ -2659,7 +2659,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10181-4"> @@ -2692,7 +2692,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10213-1"> @@ -2725,7 +2725,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10269-1"> @@ -2733,7 +2733,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10285-2"> @@ -2766,7 +2766,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath10317-2"> @@ -2818,7 +2818,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5049-7"> @@ -2826,7 +2826,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5065-3"> @@ -2884,7 +2884,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5327-2"> @@ -3017,7 +3017,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5081-8"> @@ -3025,7 +3025,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5097-0"> @@ -3033,7 +3033,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5135-8"> @@ -3066,7 +3066,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5167-6"> @@ -3099,7 +3099,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5199-9"> @@ -3132,7 +3132,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5231-4"> @@ -3165,7 +3165,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5263-5"> @@ -3198,7 +3198,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5295-4"> @@ -3231,7 +3231,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5359-0"> @@ -3283,7 +3283,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5467-7"> @@ -3291,7 +3291,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5483-5"> @@ -3299,7 +3299,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5499-4"> @@ -3307,7 +3307,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5515-6"> @@ -3315,7 +3315,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5553-5"> @@ -3348,7 +3348,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5585-3"> @@ -3381,7 +3381,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5617-0"> @@ -3414,7 +3414,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5649-4"> @@ -3447,7 +3447,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5681-5"> @@ -3480,7 +3480,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5713-8"> @@ -3513,7 +3513,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5745-4"> @@ -3546,7 +3546,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5777-6"> @@ -3598,7 +3598,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5841-2"> @@ -3606,7 +3606,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5857-0"> @@ -3614,7 +3614,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5873-6"> @@ -3622,7 +3622,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5889-2"> @@ -3630,7 +3630,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5905-8"> @@ -3663,7 +3663,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5937-3"> @@ -3696,7 +3696,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5969-3"> @@ -3729,7 +3729,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6001-7"> @@ -3762,7 +3762,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6033-5"> @@ -3795,7 +3795,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6065-8"> @@ -3828,7 +3828,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6097-0"> @@ -3861,7 +3861,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6129-2"> @@ -3894,7 +3894,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6169-2"> @@ -3902,7 +3902,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6185-2"> @@ -3935,7 +3935,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6217-8"> @@ -3968,7 +3968,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6273-5"> @@ -3976,7 +3976,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6289-4"> @@ -4009,7 +4009,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6321-0"> @@ -4065,7 +4065,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7159-1"> @@ -4073,7 +4073,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7175-5"> @@ -4106,7 +4106,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7207-6"> @@ -4139,7 +4139,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7239-4"> @@ -4147,7 +4147,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7255-7"> @@ -4180,7 +4180,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7287-1"> @@ -4213,7 +4213,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7319-8"> @@ -4221,7 +4221,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7367-9"> @@ -4254,7 +4254,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7335-3"> @@ -4287,7 +4287,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7423-6"> @@ -4295,7 +4295,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7439-8"> @@ -4328,7 +4328,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7471-3"> @@ -4361,7 +4361,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7503-0"> @@ -4369,7 +4369,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7519-4"> @@ -4402,7 +4402,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7551-8"> @@ -4435,7 +4435,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7583-7"> @@ -4443,7 +4443,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7599-4"> @@ -4476,7 +4476,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7631-1"> @@ -4509,7 +4509,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4329-0"> @@ -4517,7 +4517,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4345-1"> @@ -4541,7 +4541,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4377-8"> @@ -4574,7 +4574,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4437-7"> @@ -4582,7 +4582,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4453-8"> @@ -4606,7 +4606,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4485-3"> @@ -4639,7 +4639,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4925-8"> @@ -4647,7 +4647,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4941-1"> @@ -4680,7 +4680,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath4973-3"> @@ -4732,7 +4732,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7903-1"> @@ -4740,7 +4740,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7919-4"> @@ -4773,7 +4773,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath7951-2"> @@ -4797,7 +4797,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath17117"> @@ -4805,7 +4805,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath17121"> @@ -4838,7 +4838,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath17132"> @@ -4871,7 +4871,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath17143"> @@ -4879,7 +4879,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath17147"> @@ -4903,7 +4903,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath17158"> @@ -4991,7 +4991,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5841-3"> @@ -4999,7 +4999,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5857-5"> @@ -5007,7 +5007,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5873-66"> @@ -5015,7 +5015,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5889-3"> @@ -5023,7 +5023,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5905-9"> @@ -5058,7 +5058,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5937-4"> @@ -5093,7 +5093,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath5969-7"> @@ -5128,7 +5128,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6001-5"> @@ -5163,7 +5163,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6033-9"> @@ -5198,7 +5198,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6065-5"> @@ -5233,7 +5233,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6097-7"> @@ -5268,7 +5268,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6129-8"> @@ -5303,7 +5303,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6169-9"> @@ -5311,7 +5311,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6185-0"> @@ -5346,7 +5346,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6217-2"> @@ -5381,7 +5381,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6273-8"> @@ -5389,7 +5389,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6289-3"> @@ -5424,7 +5424,7 @@ clipPathUnits="userSpaceOnUse" id="clipPath6321-6"> @@ -5514,7 +5514,7 @@ id="bullet-char-template(57356)" transform="scale(4.8828125e-4,-4.8828125e-4)"> @@ -5522,7 +5522,7 @@ id="bullet-char-template(57354)" transform="scale(4.8828125e-4,-4.8828125e-4)"> @@ -5530,7 +5530,7 @@ id="bullet-char-template(10146)" transform="scale(4.8828125e-4,-4.8828125e-4)"> @@ -5538,7 +5538,7 @@ id="bullet-char-template(10132)" transform="scale(4.8828125e-4,-4.8828125e-4)"> @@ -5546,7 +5546,7 @@ id="bullet-char-template(10007)" transform="scale(4.8828125e-4,-4.8828125e-4)"> @@ -5554,7 +5554,7 @@ id="bullet-char-template(10004)" transform="scale(4.8828125e-4,-4.8828125e-4)"> @@ -5562,7 +5562,7 @@ id="bullet-char-template(9679)" transform="scale(4.8828125e-4,-4.8828125e-4)"> @@ -5570,7 +5570,7 @@ id="bullet-char-template(8226)" transform="scale(4.8828125e-4,-4.8828125e-4)"> @@ -5578,7 +5578,7 @@ id="bullet-char-template(8211)" transform="scale(4.8828125e-4,-4.8828125e-4)"> @@ -10281,16 +10281,6 @@ transform="matrix(-0.3,0,0,-0.3,0.69,0)" inkscape:connector-curvature="0" /> - - - - + + + + @@ -10548,7 +10548,7 @@ inkscape:label="background" style="display:none" sodipodi:insensitive="true" - transform="translate(9.5291677,71.377308)"> + transform="translate(-32.46875,315.85439)"> + transform="translate(-32.46875,315.85439)"> - - + transform="translate(-32.46875,315.85439)" + style="display:inline" + sodipodi:insensitive="true"> @@ -38088,7 +38081,7 @@ d="M 386.44699,686.89099 C 386.44699,688.40977 385.21577,689.64099 383.69699,689.64099 C 382.17821,689.64099 380.94699,688.40977 380.94699,686.89099 C 380.94699,685.37221 382.17821,684.14099 383.69699,684.14099 C 385.21577,684.14099 386.44699,685.37221 386.44699,686.89099 z" /> @@ -38154,7 +38147,7 @@ d="M 411.435,717.672 C 411.435,719.19078 410.20378,720.422 408.685,720.422 C 407.16621,720.422 405.935,719.19078 405.935,717.672 C 405.935,716.15321 407.16621,714.922 408.685,714.922 C 410.20378,714.922 411.435,716.15321 411.435,717.672 z" /> @@ -38162,39 +38155,39 @@ + sodipodi:nodetypes="cccc" /> - - + + @@ -38202,10 +38195,10 @@ id="layer2-9" inkscape:label="Eagle_speed_sensor" style="display:inline" - transform="matrix(0.77129601,0,0,0.77129601,-838.29825,-434.77767)" /> + transform="matrix(0.77129601,0,0,0.77129601,-880.29617,-190.30059)" /> + transform="matrix(0.77129601,0,0,0.77129601,-757.27445,90.740389)" /> From bf145ad76bd1cdb8c212c3c1138534aa1df9de2c Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 30 Sep 2014 13:16:29 +1000 Subject: [PATCH 196/203] Name change --- ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui index c06ca1d7d..a0f30959c 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui @@ -26,8 +26,7 @@ p, li { white-space: pre-wrap; } <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 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-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 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-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 read more regarding ESC refresh rates, please see </span><a href="http://wiki.openpilot.org/x/HIEu"><span style=" font-family:'Lucida Grande'; font-size:13pt; text-decoration: underline; color:#0000ff;">this article</span></a><span style=" font-size:10pt;"> in the OpenPilot Wiki</span></p></body></html> +<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> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop @@ -113,7 +112,7 @@ p, li { white-space: pre-wrap; } QToolButton { border: none } - Turbo PWM + Rapid ESC From 8e581a2d18d124ee87e95fd3c73e671b243babeb Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 30 Sep 2014 15:23:05 +1000 Subject: [PATCH 197/203] New buttons --- .../setupwizard/resources/bttn-rapid-dwn.png | Bin 0 -> 5705 bytes .../setupwizard/resources/bttn-rapid-up.png | Bin 0 -> 6527 bytes 2 files changed, 0 insertions(+), 0 deletions(-) create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-rapid-dwn.png create mode 100644 ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-rapid-up.png diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-rapid-dwn.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-rapid-dwn.png new file mode 100644 index 0000000000000000000000000000000000000000..04d5eb559e5dff278a78f3003a44732db812cf73 GIT binary patch literal 5705 zcmbVQXEm zlxPtm2{I9a=pl%bZ}OD)`+hvv`{O&;Is2To&sz6d`(A6E>s&hlWoF3A#K%NMMa61t zq;E;NPf{))MtaJ~Y50&bQk^3r?TA(ccVaNwA47$3Be-B7#yGSG#u9^e3-ueoXi!nn zx?`>Fh<2tXYOVyF4Enc@ObE{Rw>g!Dc8D+9)f+>ExL`c6cunYLYbO+fb<>2}Dw@Jf zef2P&Sfen1j8&MKwQHEStEwARTMMEQqDBG0VTfo*2+ju|pcbMD{S#M>^89;R77F=O zh3Ksb{VOOtQxrsx;E#bQ%E(K*!r*X-l9CKuK~YHwE(MW;!R2IOlv7C>uAruTvb)|H-?;?G(|%?AQVqT zhe+cCg#SU%#{{_gV||HO0v_@k5$!?MOo*Y&4%0MQcjzhV5Vc7S!LFGki96F>;`cctXRUHBhk3U~kA(QidcG-~GlSV~gR zKKcaLKpX~7G}hOIQr^h8Vcpb_x=3XhT;D)n0SQOK;c$c=Ob&@eAQ5n7B_#zo@*j+U zwS^&63=|cV6;zZcnLsM2Ae7`)mE?34kuao+t}^T&TVs3x5si1n{Noq<+wWhtO8?bX zP0t^LCKCLu2?U>iDgfn4AQA#R3BC|LDN@B1}JGW_WOUpOJUnw-0Q8;nL$4;HA&^&Y5+PJL6(ffzDvc@J;^-9_uQERn z^2{}<#pohd>|I^tmTktKy(v*wnzgyP(U+zYZp)Jleczzh6p zK&GUawA;Ll$$~5|(H4_fBb3sd9M|Q`uL3=BP4tMTSN_O7pmOtg9X(!VoR$d#(f97g zZ&iY`kJ#{|*FQg0mu&HdSL4_~1=8g1 zMBdCUDf>?&=>c}Q{N^tXVx~p_Pu<}~!?pMfX1C20!6QC_3RB;&VX8ey-(-LEfRb{fHIMx4zOnx+n|XLfR{=YCGRdwRan*{!x<2fa@PEXtBT z>poLu!){xc7 zGwv~6wv!Sn|MoWQcFN`Gv_GOnN{==k1=mMcHVaIm#I)I%>-H^!R@=3p zKOtO_5Yp+wxRx zsefH~$J)xAO2hK{$4cjrM_o9>+%ezYC2hBUZjrS2znZba*qRH-ynMK@E8Mq!nP^Yo2VuW?(0_lxp_;IuC| z>uZ;k_*LwI0(tZ$Kft^KXL8H@CKrI5*0yWfi`bSo?g61(7_@r!nq&jFu|8xl{d98GvZJw-X-(%Lj|_eb8*RFep1O5)7XP1>Y#mL zBh)npChXUAX0uH&Uvc!uHS6a%^~8}^a~WRGaa9_cY)>%*GUV(C59gsGrc(_iv5DG~ z{Rb&_0s&<$f>Raw)D`Oj$Kj!u)%iCJLzJm=7uCa;E?Q5|`i1>s$XI}gYV~=2i1WC& z)xTMpPosX#ftkya;nnx38C+=RPj@bjU1yD`%6hjK{cWwSlN(<@N2+L4yLd6pvsDNp zNIPmTBEm+VoY)TYEo_}sk2&Ya3(a_aNJvr^!u3FIC$K~(*%DL(?`T?b(OZ~{B0|M& z@d~=zhkPabspolts%#=HyXRPwrI+4`1NubS;+A*>_7oC}jwjUwG}zV!Mr2!dnwxXk z`PL3Ryj-_OJGkyiRS^^iWv+!?;{RAmSlW0WCzB$n6`UMa$U0|vfy_->9Rk0~n-Io% zGl23c{ZIQXF2kZOJ$n@a3x#kp=49$T^WrNPjD5?Q+wn_4Vu41#5k|NcRuDAS*-_0o zkrB5QvNnq=7)W6MAt30G*4qh=96iqKJ%-+dJI_rdghz?yME7*sKfK&5J$AX9W>7b; zvNZPDw`8-;DrMfH(l1ObU@6&qv4N>*Ap}eeTa5vyhjgW=x=QlT< zcjJ9gp_W=mHZ#DfIkQQ^PSsnA>)x3;DV2eWtfu=5KjOb8f7|OkXSMCPJM*Z#oaJf> zeZ`r`(@96Ipt!SC^)eC)CVP*@wvS8)jbdbvrNARLQ&%TWMm7dB^7^0?JaPv_)96oNGz%e+ZF?(X_8=gVqp@CN=GCct(gRg^Rsk2o z3k$oPbrukf*ihq>Y7jARql!wsG)g7>#%p5hrfYe$?TJ7^HUf#`YILNjzp^0$8Cy+| zJSpht?8Y=oMgwV_)b0dM$($QqD5foNTC15SuHAllyx9|XmYq7%{MhFXw_kaM^6b@G z)PBNG^$OS}c>b-=EtcQHHTK?S-9;OjJf7`gyn12#{Z!sjf1Kj1m{n$f>jPp9U4M)I z0B1hf6$*M$ZA6oM`#iIFy{AdZo%w zV|BX#@4x!)<3L%p+k4M~qX+OS-6|L1GI9Ng92@5{4f2Dk$R6bG$FqyfBaJ)m-|JQJhUsL~&F95kYK8!9hwzR%p6Tfl0^kcM zH@$Xf3z=e$u21i<&`sqOh& z7slv(opV%cXrW}uA%Uv(_<(!9RMvK!#78iEHJvn9BG76&>UhLuNK2y6JaJI!2na{J zn}o`Mvi!A48JySj9#p<5!)}ghYSGfO`96Hw_xxbHZl}4L^JTs$J3gP+2)W94fAd@c zXZFhC-sR>SabLfAX_Ekpis4r+d*#DZoZ8_swmFisk~g-UnxJtUw@REimcB#+fU6x= zAv?9N_WhvbX>H{vwp!;swzXOf%+7qW%aUI-9NF+lEoiTq-QnjFYF5QwvD#bj4c|+a z1{tOo@>@An1?I@~cTcmLFY0z~~9a?j>_BJc))p^U7vjp>Ms5%qp#`En=M6=L)#CWC1=yC&uy|&{Dw(=fR@7Q$>qDkDc|00czz&Pyf&inb3cXiUaI|2<(LIWe!rESMfAp938mi0R8Pn9sHK@lWOv+p zh53cKrjVeP&%+<%qYh+(7xdxfkCHf^?$%WEobPi>C%=50uk!+>M{m&G{m|md2bt@g ztY6nN&zQRT#jl@^K-D^%NJ)uIHB0#u>#JwrC5&|BN~F&8nF{el>IGrqw;qL*0&^V@+L5vE<;oN$VR8k1>rI#@aFl^*HoO@2EVUfXk7L(PZL#=t--gu~Sk;u9o zp}_<8i&_lh)RzSgPH%LKKVE z_3Xsgu&I}Tu9n3;4Xn_mY+tn&b?5%G-ye>(v^A39_;eJ@LED<8bU}VJkCjQTp?BQ# zSr;GC?DRfWr{!7~45Pc0u}OrG1i1Ccz*dAMA#PNb7y;p?bFD)0JRkAv6$K?tG+4^a z-f^au>XQr+T#Qt~FXF|;tK5A`7w$(ah7SJt)-?mGll zhelmE4&Jnn|8^s-u3Ftez49&PcTpbAo#jZDmc;Q^!3utSVjL^Qs*G@LO+5p1XT9o=A3Bj6*CF}S zI6h)KKX-?Zu;1+I#n;nsa98c&;};#d^C9TzaVC`;EA%IjXc>u@6@6DiJZ``V!tty( z*LDGa7$wAV_?_gwgNB9Y1zdmpq@5N&>3x{II(U)LonB|_)IwGUUeqZoZ+?A#t$3c~ z%f=+gNTO^~h)7WK&H+G>pp2X#L|P%^pCT}kQW%uU+CJha7m1PGL?$pIo|Lgk>+SYc zZa`ciz3Da;S9-G_D@-~jFkllF-&^Bq^_f+C$a_*um@8|b>wda&mT|9{Y#ViXpu`DKE3{_TQLPB=8@bRRMpAb6A zgY~E*!CPlkk-Ut`8rY8cwOG|zhZ~wdbzodAM4`M%hzU;}(VC|j!z8E;$LZ6jtt7eC zJ?F9D>i(dEL1B6H$-V5)rlHIqxj{Qa5r!kD%k8-M!d**&Wfp@p5k;=d`}O(?bHX~KTnam`<%j4H}Fqx h{*5rZgH9@1D)9rw+sqPH48J#bjge;hmAcNP{{b`BEvWzi literal 0 HcmV?d00001 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-rapid-up.png b/ground/openpilotgcs/src/plugins/setupwizard/resources/bttn-rapid-up.png new file mode 100644 index 0000000000000000000000000000000000000000..72ffa2cc73bf4a424d5ed638483d9e42b5af96e7 GIT binary patch literal 6527 zcmbVRWmHsM+Xkdj=|&iaZe|!#W?+VaAtWROQ9xqoW{?z+PN@MwO1hK~Nkyath7xH+ z5DDq-{P207=l#AP?|OfHXPvXpj{Caq*!N!RtouaiXrXSAvykKA;oVYGMe1I^N3I`7 zQsV2D29~aSjW9-< z_v9>HoJ7t4$cTD7x&DFU$t!rfnp--cF#rp+jh!k02(Yt)0u3cK#Wh`((6)A} zzV2u}UoCx0Uk6KBE1&`lAnz@AP2hyam;=0>9GyMnyrICqc;&A9f2PHNfWJgA4p88~ zj55;H0Vuh+qXCkl5+au3AP_)GN)!ZLxnk^GoB@9r%`IF!F;L*OrT=ol$yHPH-^9)ye+TM1WMbatu3{ijaWN;S zKYsls?Saun|F0SUQQAY_#}zH6i}rBwbho_T4{NS}z}K<+?~48iURxul?QVCyDdvty z7fVkkv@=Ex2?buSh+5fM$tfe0rNu!=6(mF%qznRq;7a0PWo5WB93(9z1pz7l!||W6 z5M>Evq_hMWA|rK;REEexz;IcR1Og0~hD(6OA^%|2oINn+&X(wZ^x9qP{TmDVuUI)H zceFXi#a-XU#qpmE(6M#FxOmvQxB`^)qyYSecFtBVULFE}w&!2oBGK-4PtjH??k-M% zzv3%r_aF3&ONmP&B$cG3#33@u5D*9+|RG}_3x*gzlt&; z!6j%Z#SZ@|T9n2B~?eXIUQF2F*c#`F&SqT_rI>ANQmj*u zv8t5NeH{yRbsTNJN}Ms&?H4jMB0>pBcL$kihaXSEv1VBD81Ci0#p zgO9jUA1LQSicn@iJuR()RgmSE*Nu(o8xv2&NfBh;w{jsYw=i;dmijXyj*pK=i|Q}q zDAJ;g&Ku)16?ajyHrYN)hq1A-n(y;_Uy3Ou$uA%H!g=v4xl$gKD=RAE0fE4ToSgWi zq$C4}@d}QWVhFY;v9EyscGZYaBHh^ft8drKi zfqqVR6H`NB@qN${Qz>_8FEFRHrbdrHIjEk5mx&~jqJ!*LxSBTv-1~xByrw!G=Fn_1NjJr=B|9QDRnt(4^#d`OIUlZ2I!2#;Yp zprBY@SrLOFi-2Ci_wu+Wc1)ZyUpc7fIGGqY;@tAXE$zn$W7)E~@4<)yv2ZeP*7T{V zsl=8uyxl{(xn;`VxjPi$qT+PMSAgU27oQVcvoHp`VbU=W&1R-sKWtYvkt^{|{4ftv zmuKf9h#UUml9qG~KV)cW`C@leG>RBq-q+3OC(6dd7f%EoPyG3I581=vtieHFRgnc& z@HIYawcnI+4}eK3LXvSSM}9Sv4p>qi$$WO=XN)&ZvX(dPQC@x&huI%v&)dAHST`e- zW%a78%x|}~hkL*2@e=uD+w5eE&4I<#OS`mRw%brqF@*d)-r1&L0a6PX0TVg65`vIwt(c-7~D_kg;uAx8e3*5qt_>0b z3RuiGe5fbW?HYc+;9<(n{50ned;JXneDa=xXw}ygq>`vsKvR7 zsoTFCIB>Mn0uz#D*#hLw$}ZMejNJ;(^8lX#2(GxS&hl&(Kg&417sXqvitx=Me1lSa zgObRO9bxgGv9w!^OkRtY4(Z>IYlPj2e`Sr zDYrIdzGPov0_1pKtf-MU8;x7>j=Vde6@f_rK{VPQ>uAkeFC7E-ZOe0l9E7mr{ryF9gIG*Ird`*`g~qjxNTFp{vP;!8x!dGR877%l@pI{w>NlQkBU``@_c-R=B~w zzW1AAIxU%!f$*NFy*C`C*+DTR57zJV`DHvR8D1YE-L9Ga_9N4aa3kx7)Y*un=j*DG zB#d;2%1=jw=7m5{P99EN#h{UrvOyM8X-J9A4cUQaTm&%L@qzEV9~U1Ei2a*qcb*{a z{o@12zKunBFs@P4mC$mH->worG~;->3L4CYt~J5*hn8%zo&w)pEgD4p{`d{`g;N$b zeVII8-ufn%`*FjFEsW7A=~re+)y;a9uv1IiaXD>=8VJhsGeS$BlNa1k_E1{u6h>e; zG&vT8!>Jdu4;SY956ClPcJGi?e`|c*$cNhL5c_TXaprgjp8|1zJBWlzD&Tzvw20?c zt@lD%=M7p9-eNF8(!+*&Z&wMiPv5;;I@df|KPj5_$R0k+ZaPw7AkE#{KIIErKO5?t zGt>ZA%lNVBjeB`ezPn_=XYP6V$fuXPhNGwct=~3Z-|sb{n@NbqyVG@qGegN7LIRz^ zr573E!u+x^UiFNR9Os{tu%w-7h^1+2wBa5V8<#Nf(dE`Q)80K~?~-uYVA=O5l<6^-MJBB=Zs*5YKQwxFsU2jw-lcHd>MAF6B*P!Q${p|i9B0XgZ+*nvb4BTv{bh@! zk!cX7p7T6gbF^l@QqJ#B(|lrYkQoJ$C$ldtJuX2~Y#j1hny+Ey~y+U?y4t62sTX0mIhw1ehAC0%VN`>T5;wL{Jm$~IZ=_S+`js|BpKi3 zw&x3Zt=$D%`BFCUpJk7vhXji)(Bf`LYR|SLltTF4j0<6#-(XNy1(VXB*H|CztVZ}% zu4H`u*)P$&gzKn2-|=!fmB0;tU;WL$fKT-5DDNgEP$ALOjzxEt4~^?gi2y^f2}0tO z>fQP2ls{l`rFpxL8$KY&5T&v&SU9HTJ+LOv%zP{HUb23l-u0rnFDhMM6GT9{kv!QI zrL?s0=zH|e+M-@sG>ukvskNORPq9PV7P728MC8z7@{PXrrS6mV+$-hZ@r^?49`+|H zLj#nV8vNQFk)f(me4Zi;44EDEB!dkbTbZy+;?Z$RwM>gGU>=Ky_!7A%ypS}H0!t;s3H-kGRhASG^ zk^PI-=bjF^{V<0>Ns=D2RfBdM97$g7d_dqahIDwuIM!TUV<_{A?c_H{V;B($DFih# zUSOm?QmC@TB=F+gsILRdaz}e}p2}z0yL2b)K~#r=L%&tZptdZ5q1bFyam%=X{%eTN zhJat-PS%eG%;ZxzXQEoVTLm$2_zG4x(q_l^aeKR;Aw*k^m*9ja&=>Cl2Qj=IAp3^s zCYu2de)6P!CFP?1+sf_%RcmV4_o5lH(VHGTB~PRBj2^4;Q_TGsY}p!($3}G{hvdMy z-WqKdom@kG#@js4VjlzWv&6=+pkdz%P9gQ#r;8_~T)Q$|t`HTJ3}$YeiLFot)l= z)E+|nRhTbRm0;%T>C0n)BTvTzTGt9n9y;~s0+zH7zl2I+o~|S&r?ibF{1j)3n`l}i zY-&2VfWatHwC1(}U$SLc{LUVR$Y(s~wOCv{9(#RLUxs2l-#@>pY08IuQLPk(wSVvG zThx)tWfl2v-e@zocf4;Dyum6b!SROdzOc|B1uFjn4e`G;5um8n zTSydQrMwtMisU@P-PN%+m9~5hrzhOZ7MPQqTxt< zHvZn1Pp2kU0lU#tdqp%nW@B6*C4liDa$MF(EYeOf-3>729(I zT>J{NM=9aQ?q->I^7#l;_93fc0X3^%pB@GhFz-)xb{6+VtIpaTwYt~DTirT)q5pG0 z`Qb%0#5Wo-*-qq!0uv3WU3U7JrS3a$6cCPJ6AU**v(eD+Sq};q1LFO6US0-|#l3D* zoKjF`SIafMIO1vWI>C6fa)uqO$P)2%Pk;Y(MW!q@l`ql!D!o~Uq1*qU*(Zb7B^GuImug>{!;(P}MPl!$o{h?%Fi51DPNdXx+Jnk|r zJNvbc)BY-K`8m5%KkDuU zr@jyjYQ8a(eb;vTJ-18f-RS`pLLSGUn4uMl1MjP~_O^TmCjaEY(L0?1lj}vZwQ%sk z6kSX*sW%C+ucKcrLOGo1UG3>@Y&Ij8#^-}zn$7TcI5{|PuFe33x(vBt%UL*$*@hS` z7cR^dx|++v%1VL>yuq^QU~lg}73I3W$x2W`d8(Zy8-ALn!_K<67y2lN)O#jywGKAY zRVg356`zH=Y?YAlU!{rNrsn!4Vva=UlP+m$eF+w*j~dBe3(K8rZSWkB5zcw}d`hVQ z_&B4zTZA8_B(yk3=6?OLTi9azR0S9y6-dDQLLKSlCG9{Q(pp20yMK4sZd@{d=$tQ< zc-3|G9dm=%%FTs4GErWigj*X|tv{ovdPhh2C(L5dviYuE!S_NVh~HgRzJ1$Y*fkYI zi(9#A;MxKrl+$^(pfHheQTawOd}#Xb*{_@Z8UYrTaN z+?dbeb8u^1rrO%(c2}I5f7j zS*zXOL|bU)B=l9hiqOhzPt8JA)xRhA%?Bv8^fjeXP0Mr9EA+5OL~_DoRkN2l$im*` z8m*M>bhBkeo`yeI*c9wMyjUzL%l|%3>hU!jpyY@ISZk?vXb!7zLN|!_h!F zC<@yv1z)%his(%s;%x@TEv|;h*`OvN9;0z3PPQnI5A}l%%+w2&$)t3l*kkcn%_wUP zIX*sQ^&X0Q_kpB)n$C=Fb#G-wRJFNk^k5r#+!qJIl#TlJ*f%>A)JJjh263nMZ|ypD zs@Wi!j|m7ueku73)2k}JZlQ9s#K(v8(UabOz%R?I5jQRHbZiy8F?q|9U?-)_4!au#OPSGUnx1MOdDAS@9a=Mikgv; zuMdWg&&;=Oz@NYCgGTd2$Ha6#q@zkud<@VsnvZ#$8~Y$KEQEv-oX)BcAfK0?pF0{& z=!w6DZ@^*Jgdr;|EOZAyzvWw7y+OOYc+1(0Hqrl{eJ88m z+wryDYb!%|5OL#?o(zN^hs`Xk*+r0Ci7WXZKYkn+6cVcJRxOY&O?fVa9Y6}2CF`zW z)oZQ$U-77^sd-&TimIBR!;WG5x+G?TC`IN`N;^+CXey_dczU?IA?&O|fAwp_h2IAI zeLyCzZyTj>*_9AXgzyYpK+@*9OE~R(ID@(}NQZuD$2O0#buM(2zaw{@nPr zPz8W?MU+oO#h2!vQ%B!8#?keosMJ5-AVXuRRVo3x^}nDLx^@O>Jw1deNBe^Co7W{j zZLX9|Zr?E76(@eIauMO|eX*9l5iE|o4~nlXeTG#pG~B85P50l;Qmmux_U8@2i|eD? zzYjVgB%IFDR}pd}3Tf*bF5j0F!p6ty5HrKQQE}0NWMDFH+R~Bk!h29~89Jj^6I$p} xn3(RR4koi8^A7GIq0eK|?=BqMz9P7Zcl1c7E}rT<#BY{{XSOzM%jB literal 0 HcmV?d00001 From e54d7865af9ca4d9a49d40e25a4c344609c3f049 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 30 Sep 2014 15:24:34 +1000 Subject: [PATCH 198/203] Add to resources --- ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc index c320a20e8..898f43f5f 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc +++ b/ground/openpilotgcs/src/plugins/setupwizard/wizardResources.qrc @@ -29,6 +29,8 @@ resources/bttn-calculate-up.png resources/bttn-turbo-down.png resources/bttn-turbo-up.png + resources/bttn-rapid-up.png + resources/bttn-rapid-dwn.png resources/bttn-servo-digital-dwn.png resources/bttn-servo-digital-up.png resources/bttn-servo-standard-dwn.png From 459173300840c18368b086e6b637b0f593e98214 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 30 Sep 2014 15:37:08 +1000 Subject: [PATCH 199/203] Add new Buttons to Wizard --- ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui index a0f30959c..a086e0f84 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/escpage.ui @@ -116,8 +116,8 @@ p, li { white-space: pre-wrap; } - :/setupwizard/resources/bttn-turbo-up.png - :/setupwizard/resources/bttn-turbo-down.png:/setupwizard/resources/bttn-turbo-up.png + :/setupwizard/resources/bttn-rapid-up.png + :/setupwizard/resources/bttn-rapid-dwn.png:/setupwizard/resources/bttn-rapid-up.png From 34628cd194eda0afd1f537f02f846bcebc8ead1d Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 30 Sep 2014 15:40:02 +1000 Subject: [PATCH 200/203] Update rates --- ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp | 2 +- .../src/plugins/setupwizard/vehicleconfigurationhelper.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index f19c6fd51..749ccc179 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -363,7 +363,7 @@ QString SetupWizard::getSummaryText() summary.append(tr("Standard ESC (50 Hz)")); break; case ESC_RAPID: - summary.append(tr("Rapid ESC (400 Hz)")); + summary.append(tr("Rapid ESC (500 Hz)")); break; default: summary.append(tr("Unknown")); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index f8e7c29a7..08c1bfa27 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -45,7 +45,7 @@ #include const qint16 VehicleConfigurationHelper::LEGACY_ESC_FREQUENCE = 50; -const qint16 VehicleConfigurationHelper::RAPID_ESC_FREQUENCE = 400; +const qint16 VehicleConfigurationHelper::RAPID_ESC_FREQUENCE = 500; const qint16 VehicleConfigurationHelper::ANALOG_SERVO_FREQUENCE = 50; const qint16 VehicleConfigurationHelper::DIGITAL_SERVO_FREQUENCE = 333; From 0556f6f6ad97d9e703cd5b7cb6646bae3257493f Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 30 Sep 2014 15:47:01 +1000 Subject: [PATCH 201/203] uncrusty --- .../src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h | 1 - .../src/plugins/config/configstabilizationwidget.cpp | 1 + 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h index 1821190c0..5e25d99d3 100644 --- a/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h +++ b/ground/openpilotgcs/src/plugins/config/cfg_vehicletypes/configfixedwingwidget.h @@ -71,7 +71,6 @@ protected: private slots: virtual void setupUI(QString airframeType); virtual bool throwConfigError(QString airframeType); - }; #endif // CONFIGFIXEDWINGWIDGET_H diff --git a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp index e8dbadbee..9c8af326d 100644 --- a/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp +++ b/ground/openpilotgcs/src/plugins/config/configstabilizationwidget.cpp @@ -344,6 +344,7 @@ void ConfigStabilizationWidget::onBoardConnected() void ConfigStabilizationWidget::pidBankChanged(int index) { bool dirty = isDirty(); + updateObjectFromThrottleCurve(); foreach(QTabBar * tabBar, m_pidTabBars) { disconnect(tabBar, SIGNAL(currentChanged(int)), this, SLOT(pidBankChanged(int))); From ffdfa62d2207b8dcb02becf7641cfad5c72ea8f1 Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 30 Sep 2014 16:54:24 +1000 Subject: [PATCH 202/203] Bandwidth testing --- shared/uavobjectdefinition/attitudestate.xml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/shared/uavobjectdefinition/attitudestate.xml b/shared/uavobjectdefinition/attitudestate.xml index 98ceaa3c7..0d5dc0c08 100644 --- a/shared/uavobjectdefinition/attitudestate.xml +++ b/shared/uavobjectdefinition/attitudestate.xml @@ -10,7 +10,7 @@ - + From 4c88d878d407d2d4a6a9a818bcc24d9d321b7b3e Mon Sep 17 00:00:00 2001 From: Fredrik Larson Date: Tue, 30 Sep 2014 23:32:26 +1000 Subject: [PATCH 203/203] add 500 as an option --- .../openpilotgcs/src/plugins/config/output.ui | 54 ++++++++++++++----- 1 file changed, 42 insertions(+), 12 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/config/output.ui b/ground/openpilotgcs/src/plugins/config/output.ui index 575b03e58..a09aa8f88 100644 --- a/ground/openpilotgcs/src/plugins/config/output.ui +++ b/ground/openpilotgcs/src/plugins/config/output.ui @@ -282,8 +282,8 @@ - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. + Setup "RapidESC" here: usual value is 500 Hz for multirotor airframes. + @@ -320,6 +320,11 @@ Leave at 50Hz for fixed wing. 400 + + + 500 + + @@ -340,8 +345,8 @@ Leave at 50Hz for fixed wing. - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. + Setup "RapidESC" here: usual value is 500 Hz for multirotor airframes. + @@ -378,6 +383,11 @@ Leave at 50Hz for fixed wing. 400 + + + 500 + + @@ -420,8 +430,8 @@ Leave at 50Hz for fixed wing. - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. + Setup "RapidESC" here: usual value is 500 Hz for multirotor airframes. + @@ -458,6 +468,11 @@ Leave at 50Hz for fixed wing. 400 + + + 500 + + @@ -478,8 +493,8 @@ Leave at 50Hz for fixed wing. - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. + Setup "RapidESC" here: usual value is 500 Hz for multirotor airframes. + @@ -516,6 +531,11 @@ Leave at 50Hz for fixed wing. 400 + + + 500 + + @@ -546,8 +566,8 @@ Leave at 50Hz for fixed wing. - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. + Setup "RapidESC" here: usual value is 500 Hz for multirotor airframes. + @@ -584,6 +604,11 @@ Leave at 50Hz for fixed wing. 400 + + + 500 + + @@ -604,8 +629,8 @@ Leave at 50Hz for fixed wing. - Setup "TurboPWM" here: usual value is 400 Hz for multirotor airframes. -Leave at 50Hz for fixed wing. + Setup "RapidESC" here: usual value is 500 Hz for multirotor airframes. + @@ -642,6 +667,11 @@ Leave at 50Hz for fixed wing. 400 + + + 500 + +