From c483d429375c28506c4b8fe441a2898cf6d46ee0 Mon Sep 17 00:00:00 2001 From: Fredrik Arvidsson Date: Tue, 21 Aug 2012 01:07:38 +0200 Subject: [PATCH] OP-39 Added mixer and motor configuration for Hexa and Octocopters. Changed so that the Flex port is set to be serial telemetry port by default. Added some description texts for the different multirotor types. Fixed disabling/enabling of Cancel and Back buttons during processing like bias calculation and saving of configuration. Converted summary text to html and added some formatting of the text. Added message if no controller is connected on saving the configuration. --- .../setupwizard/pages/controllerpage.ui | 4 +- .../plugins/setupwizard/pages/flashpage.cpp | 17 +- .../plugins/setupwizard/pages/inputpage.ui | 6 +- .../setupwizard/pages/levellingpage.cpp | 10 +- .../setupwizard/pages/levellingpage.ui | 6 +- .../plugins/setupwizard/pages/multipage.cpp | 50 +- .../src/plugins/setupwizard/pages/multipage.h | 2 + .../plugins/setupwizard/pages/multipage.ui | 3 +- .../plugins/setupwizard/pages/outputpage.ui | 8 +- .../plugins/setupwizard/pages/startpage.ui | 4 +- .../plugins/setupwizard/pages/summarypage.ui | 15 +- .../src/plugins/setupwizard/setupwizard.cpp | 22 +- .../vehicleconfigurationhelper.cpp | 480 +++++++++++++++++- 13 files changed, 569 insertions(+), 58 deletions(-) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui index 61a6d1ff7..14d37b737 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/controllerpage.ui @@ -29,9 +29,9 @@ 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;">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; font-size:8pt;"></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 we need to know what kind of OpenPilot board you want the wizard to create a configuration for. The wizard will try to automatically detect what type of board you have connected.</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;">To continue the wizard needs to know what kind of OpenPilot controller you want to create a configuration for. The wizard will try to automatically detect what type of board you have when connected.</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Please connect the board to a free usb port on your computer, or if a serial modem like BlueTooth, PipX or other is used, then power up the board and select the device to connect with from the list below. Then press Connect.</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;">Please connect the board to a free usb port on your computer, or if a serial modem like BlueTooth, PipX or other is used, power up the board and select the device to connect with from the list below. Then press 'Connect'.</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;">If the board already is connected and succesfully detected the board type will allready be displayed. You can disconnect and select another device if you need to detect another board.</span></p></body></html> diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/flashpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/flashpage.cpp index f7438c8be..79014eaf5 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/flashpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/flashpage.cpp @@ -25,6 +25,7 @@ * 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA */ +#include #include "flashpage.h" #include "ui_flashpage.h" #include "setupwizard.h" @@ -55,14 +56,28 @@ bool FlashPage::isComplete() const void FlashPage::writeToController() { + if(!getWizard()->getConnectionManager()->isConnected()) { + QMessageBox msgBox; + msgBox.setText(tr("An OpenPilot controller must be connected to your computer to save the " + "configuration.\nPlease connect your OpenPilot controller to your computer and try again.")); + msgBox.setStandardButtons(QMessageBox::Ok); + msgBox.setDefaultButton(QMessageBox::Ok); + msgBox.exec(); + return; + } + ui->saveButton->setEnabled(false); + getWizard()->button(QWizard::CancelButton)->setEnabled(false); + getWizard()->button(QWizard::BackButton)->setEnabled(false); VehicleConfigurationHelper helper(getWizard()); connect(&helper, SIGNAL(saveProgress(int, int, QString)),this, SLOT(saveProgress(int, int, QString))); m_successfulWrite = helper.setupVehicle(); disconnect(&helper, SIGNAL(saveProgress(int, int, QString)),this, SLOT(saveProgress(int, int, QString))); - emit completeChanged(); ui->saveProgressLabel->setText(QString("%2").arg(m_successfulWrite ? "green" : "red", ui->saveProgressLabel->text())); ui->saveButton->setEnabled(true); + getWizard()->button(QWizard::CancelButton)->setEnabled(true); + getWizard()->button(QWizard::BackButton)->setEnabled(true); + emit completeChanged(); } void FlashPage::saveProgress(int total, int current, QString description) diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.ui index 0512ac8c3..75cd62c94 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/inputpage.ui @@ -29,7 +29,7 @@ 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;">OpenPilot basic input signal configuration</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:12pt; font-weight:600;"></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 leave the default option selected and continue the 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-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;"></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Some input options require the OpenPilot controller to be rebooted before the changes can take place. If an option that requires a reboot is selected the controller will need to be rebooted at the end of this wizard after the configuration is written to the controller.</span></p></body></html> @@ -44,9 +44,9 @@ p, li { white-space: pre-wrap; } 20 - 200 + 220 561 - 181 + 160 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.cpp index 5438f1a83..10afada80 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.cpp @@ -62,7 +62,7 @@ void LevellingPage::performLevelling() if(!getWizard()->getConnectionManager()->isConnected()) { QMessageBox msgBox; msgBox.setText(tr("An OpenPilot controller must be connected to your computer to perform bias " - "calculations.\nPlease connect your OpenPilot controller to continue.")); + "calculations.\nPlease connect your OpenPilot controller to your computer and try again.")); msgBox.setStandardButtons(QMessageBox::Ok); msgBox.setDefaultButton(QMessageBox::Ok); msgBox.exec(); @@ -74,11 +74,15 @@ void LevellingPage::performLevelling() // Measure every 100ms * 100times = 10s m_levellingUtil = new LevellingUtil(BIAS_CYCLES, BIAS_PERIOD); } + emit completeChanged(); + connect(m_levellingUtil, SIGNAL(progress(long,long)), this, SLOT(levellingProgress(long,long))); connect(m_levellingUtil, SIGNAL(done(accelGyroBias)), this, SLOT(levellingDone(accelGyroBias))); connect(m_levellingUtil, SIGNAL(timeout(QString)), this, SLOT(levellingTimeout(QString))); + getWizard()->button(QWizard::CancelButton)->setEnabled(false); + getWizard()->button(QWizard::BackButton)->setEnabled(false); ui->levelButton->setEnabled(false); - emit completeChanged(); + m_levellingUtil->start(); } @@ -118,5 +122,7 @@ void LevellingPage::stopLevelling() disconnect(m_levellingUtil, SIGNAL(done(accelGyroBias)), this, SLOT(levellingDone(accelGyroBias))); disconnect(m_levellingUtil, SIGNAL(timeout(QString)), this, SLOT(levellingTimeout(QString))); ui->levelButton->setEnabled(true); + getWizard()->button(QWizard::CancelButton)->setEnabled(true); + getWizard()->button(QWizard::BackButton)->setEnabled(true); } } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.ui index e86ae3eaf..da1f582e7 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/levellingpage.ui @@ -27,13 +27,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: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;">OpenPilot controller levelling procedure</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:12pt; font-weight:600;">OpenPilot controller levelling 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;"></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 step can only be performed if you have the OpenPilot controller connected and identified by the first step in this wizard.</span></p> -<p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> <p style=" 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 about in which position the vehicle normally is considered to be level. To be able to successfully perform these measurements you need to place the vehicle on a flat and as level as possible surface. Example of such surfaces could be a table top or the floor. Be careful to assure 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;"></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 levelling, 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 levelling, 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/multipage.cpp b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp index 9963422ea..37419eabb 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.cpp @@ -69,16 +69,42 @@ bool MultiPage::validatePage() void MultiPage::setupMultiTypesCombo() { - ui->typeCombo->addItem("Tricopter", SetupWizard::MULTI_ROTOR_TRI_Y); - ui->typeCombo->addItem("Quadcopter X", SetupWizard::MULTI_ROTOR_QUAD_X); - ui->typeCombo->addItem("Quadcopter +", SetupWizard::MULTI_ROTOR_QUAD_PLUS); - ui->typeCombo->addItem("Hexacopter", SetupWizard::MULTI_ROTOR_HEXA); - ui->typeCombo->addItem("Hexacopter Coax (Y6)", SetupWizard::MULTI_ROTOR_HEXA_COAX_Y); - ui->typeCombo->addItem("Hexacopter H", SetupWizard::MULTI_ROTOR_HEXA_H); - ui->typeCombo->addItem("Octocopter", SetupWizard::MULTI_ROTOR_OCTO); - ui->typeCombo->addItem("Octocopter Coax X", SetupWizard::MULTI_ROTOR_OCTO_COAX_X); - ui->typeCombo->addItem("Octocopter Coax +", SetupWizard::MULTI_ROTOR_OCTO_COAX_PLUS); - ui->typeCombo->addItem("Octocopter V", SetupWizard::MULTI_ROTOR_OCTO_V); + 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 aft motor. " + "The fore 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 rotates clockwise " + "and two counter clockwise. The motors positioned diagonal of each other rotates 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 fore and aft rotates in one direction and the motors steerboard and port rotates in the other. " + "This setup was one of the first to be used and is still used for sport flying. This configuration is not that well suited " + "for FPV since the fore rotor tend to be in the way of the camera."); + + ui->typeCombo->addItem(tr("Hexacopter"), SetupWizard::MULTI_ROTOR_HEXA); + m_descriptions << tr("Hexacopter"); + + ui->typeCombo->addItem(tr("Hexacopter Coax (Y6)"), SetupWizard::MULTI_ROTOR_HEXA_COAX_Y); + m_descriptions << tr("Hexacopter Coax (Y6)"); + + ui->typeCombo->addItem(tr("Hexacopter H"), SetupWizard::MULTI_ROTOR_HEXA_H); + m_descriptions << tr("Hexacopter H"); + + 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() @@ -94,9 +120,7 @@ void MultiPage::updateImageAndDescription() { SetupWizard::VEHICLE_SUB_TYPE type = (SetupWizard::VEHICLE_SUB_TYPE) ui->typeCombo->itemData(ui->typeCombo->currentIndex()).toInt(); QString elementId = ""; - QString description = "Descriptive text with information about "; - description.append(ui->typeCombo->currentText()); - description.append(" multirotors."); + QString description = m_descriptions.at(ui->typeCombo->currentIndex()); switch(type) { case SetupWizard::MULTI_ROTOR_TRI_Y: diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h index 0ffa84a36..a4d8ebf42 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.h @@ -30,6 +30,7 @@ #include #include +#include #include "abstractwizardpage.h" @@ -54,6 +55,7 @@ private: void setupMultiTypesCombo(); QGraphicsSvgItem *multiPic; void updateAvailableTypes(); + QList m_descriptions; private slots: void updateImageAndDescription(); diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui index 2c33fb4d5..d6d62f704 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/multipage.ui @@ -31,7 +31,8 @@ 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; 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-size:10pt;">This part of the wizard will set up the OpenPilot controller for use with a flying platform with multiple rotors. The wizard supports the most common types of multirotors. Other variants of multirotors can be configured by using custom configuration options in the configuration plugin in GCS.</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Please select the type of multirotor you want to create a configuration for below:</span></p></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 multirotor you want to create a configuration for below:</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">(Depending on input configuration all types may not be available to select from the list.)</span></p></body></html> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui index 7b290cece..37cd5c209 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/outputpage.ui @@ -44,9 +44,9 @@ p, li { white-space: pre-wrap; } 20 - 200 + 220 561 - 181 + 161 @@ -64,7 +64,7 @@ p, li { white-space: pre-wrap; } - 160 + 290 40 100 100 @@ -93,7 +93,7 @@ p, li { white-space: pre-wrap; } - 30 + 160 40 100 100 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui index 0f656f35c..e6a293d90 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/startpage.ui @@ -36,12 +36,12 @@ 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:12pt; font-weight:600;">Welcome to the OpenPilot Setup Wizard</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:8pt;"></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This wizard will guide you through the basic steps of setting up your OpenPilot controller board. The following pages contains simple questions about your vehicle and its characteristics. </span></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">From the information </span><span style=" font-size:10pt;">gathered</span><span style=" font-size:10pt;"> the wizard will create a baseline configuration that should be good enough for you to get a quick start using your OpenPilot product.</span></p> +<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">From the information gathered the wizard will create a baseline configuration that should be good enough for you to get a quick start using your OpenPilot product.</span></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">The baseline configuration can, if desired, be uploaded to the OpenPilot Controller board at the end of this wizard.</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> <p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">This wizard does not contain the full range of settings available in the GCS Config plugin. All configuration parameters can be changed at later by using the GCS Config plugin.</span></p> <p style="-qt-paragraph-type:empty; margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px; font-size:10pt;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">Ok, lets start the configuration by clicking on the 'Next' button 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;">Ok, lets start the configuration by clicking on the 'Next'/'Continue' button below.</span></p></body></html> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop diff --git a/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui index 4c91ec369..68f0ea8fa 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui +++ b/ground/openpilotgcs/src/plugins/setupwizard/pages/summarypage.ui @@ -30,10 +30,9 @@ 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: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;"></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. The information required to create a basic OpenPilot controller configuration has been collected and a configuration can be created and saved.</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 OpenPilotController 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;"></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 schematic picture illustrating how to connect selected hardware and the OpenPilotController 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;"></p> -<p style=" margin-top:0px; margin-bottom:0px; margin-left:0px; margin-right:0px; -qt-block-indent:0; text-indent:0px;"><span style=" font-size:10pt;">To complete the wizard and write the confguration directly to the OpenPilot controller, or if no OpenPilotController is connected save the configuration to disk for later usage, please continue to the next and last step of this wizard.</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 complete the wizard and write the configuration directly to the OpenPilot controller please continue to the next and last step of this wizard.</span></p></body></html> Qt::AlignLeading|Qt::AlignLeft|Qt::AlignTop @@ -46,9 +45,9 @@ p, li { white-space: pre-wrap; } 20 - 240 + 220 561 - 140 + 160 @@ -67,7 +66,7 @@ p, li { white-space: pre-wrap; } 440 - 20 + 34 100 100 @@ -97,9 +96,9 @@ Illustration 20 - 20 + 30 400 - 100 + 110 diff --git a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp index 155accd14..942eb5d93 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/setupwizard.cpp @@ -107,7 +107,7 @@ int SetupWizard::nextId() const QString SetupWizard::getSummaryText() { QString summary = ""; - summary.append(tr("Controller type: ")); + summary.append("").append(tr("Controller type: ")).append(""); switch(getControllerType()) { case CONTROLLER_CC: @@ -127,15 +127,15 @@ QString SetupWizard::getSummaryText() break; } - summary.append('\n'); - summary.append(tr("Vehicle type: ")); + summary.append("
"); + summary.append("").append(tr("Vehicle type: ")).append(""); switch (getVehicleType()) { case VEHICLE_MULTI: summary.append(tr("Multirotor")); - summary.append('\n'); - summary.append(tr("Vehicle sub type: ")); + summary.append("
"); + summary.append("").append(tr("Vehicle sub type: ")).append(""); switch (getVehicleSubType()) { case SetupWizard::MULTI_ROTOR_TRI_Y: @@ -187,8 +187,8 @@ QString SetupWizard::getSummaryText() summary.append(tr("Unknown")); } - summary.append('\n'); - summary.append(tr("Input type: ")); + summary.append("
"); + summary.append("").append(tr("Input type: ")).append(""); switch (getInputType()) { case INPUT_PWM: @@ -207,8 +207,8 @@ QString SetupWizard::getSummaryText() summary.append(tr("Unknown")); } - summary.append('\n'); - summary.append(tr("ESC type: ")); + summary.append("
"); + summary.append("").append(tr("ESC type: ")).append(""); switch (getESCType()) { case ESC_LEGACY: @@ -221,8 +221,8 @@ QString SetupWizard::getSummaryText() summary.append(tr("Unknown")); } - summary.append('\n'); - summary.append(tr("Accel & Gyro bias calibrated: ")); + summary.append("
"); + summary.append("").append(tr("Accel & Gyro bias calibrated: ")).append(""); if (isLevellingPerformed()) { summary.append(tr("Yes")); } diff --git a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp index 0de560ec4..125f5d938 100644 --- a/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp +++ b/ground/openpilotgcs/src/plugins/setupwizard/vehicleconfigurationhelper.cpp @@ -96,7 +96,10 @@ void VehicleConfigurationHelper::applyHardwareConfiguration() case VehicleConfigurationSource::CONTROLLER_CC3D: // Reset all ports data.CC_RcvrPort = HwSettings::CC_RCVRPORT_DISABLED; - data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_DISABLED; + + //Default flexiport to be active telemetry link + data.CC_FlexiPort = HwSettings::CC_FLEXIPORT_TELEMETRY; + data.CC_MainPort = HwSettings::CC_MAINPORT_DISABLED; switch(m_configSource->getInputType()) { @@ -500,10 +503,13 @@ void VehicleConfigurationHelper::resetGUIData() void VehicleConfigurationHelper::setupTriCopter() { // Typical vehicle setup - // 1. Setup and apply mixer + // 1. Setup mixer data // 2. Setup GUI data + // 3. Apply changes mixerSettings mixer; + GUIConfigDataUnion guiSettings = getGUIConfigData(); + mixer.channels[0].type = MIXER_TYPE_MOTOR; mixer.channels[0].throttle1 = 100; mixer.channels[0].throttle2 = 0; @@ -532,15 +538,12 @@ void VehicleConfigurationHelper::setupTriCopter() mixer.channels[3].pitch = 0; mixer.channels[3].yaw = 100; - applyMixerConfiguration(mixer); - - GUIConfigDataUnion guiSettings = getGUIConfigData(); - guiSettings.multi.VTOLMotorNW = 1; guiSettings.multi.VTOLMotorNE = 2; guiSettings.multi.VTOLMotorS = 3; guiSettings.multi.TRIYaw = 4; + applyMixerConfiguration(mixer); applyMultiGUISettings(SystemSettings::AIRFRAMETYPE_TRI, guiSettings); } @@ -646,13 +649,476 @@ void VehicleConfigurationHelper::setupQuadCopter() } applyMixerConfiguration(mixer); applyMultiGUISettings(frame, guiSettings); - } void VehicleConfigurationHelper::setupHexaCopter() { + mixerSettings mixer; + GUIConfigDataUnion guiSettings = getGUIConfigData(); + SystemSettings::AirframeTypeOptions frame; + + switch(m_configSource->getVehicleSubType()) + { + case VehicleConfigurationSource::MULTI_ROTOR_HEXA: { + frame = SystemSettings::AIRFRAMETYPE_HEXA; + + mixer.channels[0].type = MIXER_TYPE_MOTOR; + mixer.channels[0].throttle1 = 100; + mixer.channels[0].throttle2 = 0; + mixer.channels[0].roll = 0; + mixer.channels[0].pitch = 33; + mixer.channels[0].yaw = -33; + + mixer.channels[1].type = MIXER_TYPE_MOTOR; + mixer.channels[1].throttle1 = 100; + mixer.channels[1].throttle2 = 0; + mixer.channels[1].roll = -50; + mixer.channels[1].pitch = 33; + mixer.channels[1].yaw = 33; + + mixer.channels[2].type = MIXER_TYPE_MOTOR; + mixer.channels[2].throttle1 = 100; + mixer.channels[2].throttle2 = 0; + mixer.channels[2].roll = -50; + mixer.channels[2].pitch = -33; + mixer.channels[2].yaw = -33; + + mixer.channels[3].type = MIXER_TYPE_MOTOR; + mixer.channels[3].throttle1 = 100; + mixer.channels[3].throttle2 = 0; + mixer.channels[3].roll = 0; + mixer.channels[3].pitch = -33; + mixer.channels[3].yaw = 33; + + mixer.channels[4].type = MIXER_TYPE_MOTOR; + mixer.channels[4].throttle1 = 100; + mixer.channels[4].throttle2 = 0; + mixer.channels[4].roll = 50; + mixer.channels[4].pitch = -33; + mixer.channels[4].yaw = -33; + + mixer.channels[5].type = MIXER_TYPE_MOTOR; + mixer.channels[5].throttle1 = 100; + mixer.channels[5].throttle2 = 0; + mixer.channels[5].roll = 50; + mixer.channels[5].pitch = 33; + mixer.channels[5].yaw = 33; + + guiSettings.multi.VTOLMotorN = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorSE = 3; + guiSettings.multi.VTOLMotorS = 4; + guiSettings.multi.VTOLMotorSW = 5; + guiSettings.multi.VTOLMotorNW = 6; + + break; + } + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_COAX_Y: { + frame = SystemSettings::AIRFRAMETYPE_HEXACOAX; + + mixer.channels[0].type = MIXER_TYPE_MOTOR; + mixer.channels[0].throttle1 = 100; + mixer.channels[0].throttle2 = 0; + mixer.channels[0].roll = 100; + mixer.channels[0].pitch = 25; + mixer.channels[0].yaw = -66; + + mixer.channels[1].type = MIXER_TYPE_MOTOR; + mixer.channels[1].throttle1 = 100; + mixer.channels[1].throttle2 = 0; + mixer.channels[1].roll = 100; + mixer.channels[1].pitch = 25; + mixer.channels[1].yaw = 66; + + mixer.channels[2].type = MIXER_TYPE_MOTOR; + mixer.channels[2].throttle1 = 100; + mixer.channels[2].throttle2 = 0; + mixer.channels[2].roll = -100; + mixer.channels[2].pitch = 25; + mixer.channels[2].yaw = -66; + + mixer.channels[3].type = MIXER_TYPE_MOTOR; + mixer.channels[3].throttle1 = 100; + mixer.channels[3].throttle2 = 0; + mixer.channels[3].roll = -100; + mixer.channels[3].pitch = 25; + mixer.channels[3].yaw = 66; + + mixer.channels[4].type = MIXER_TYPE_MOTOR; + mixer.channels[4].throttle1 = 100; + mixer.channels[4].throttle2 = 0; + mixer.channels[4].roll = 0; + mixer.channels[4].pitch = -50; + mixer.channels[4].yaw = -66; + + mixer.channels[5].type = MIXER_TYPE_MOTOR; + mixer.channels[5].throttle1 = 100; + mixer.channels[5].throttle2 = 0; + mixer.channels[5].roll = 0; + mixer.channels[5].pitch = -50; + mixer.channels[5].yaw = 66; + + guiSettings.multi.VTOLMotorNW = 1; + guiSettings.multi.VTOLMotorW = 2; + guiSettings.multi.VTOLMotorNE = 3; + guiSettings.multi.VTOLMotorE = 4; + guiSettings.multi.VTOLMotorS = 5; + guiSettings.multi.VTOLMotorSE = 6; + + break; + } + case VehicleConfigurationSource::MULTI_ROTOR_HEXA_H: { + frame = SystemSettings::AIRFRAMETYPE_HEXAX; + + mixer.channels[0].type = MIXER_TYPE_MOTOR; + mixer.channels[0].throttle1 = 100; + mixer.channels[0].throttle2 = 0; + mixer.channels[0].roll = -33; + mixer.channels[0].pitch = 50; + mixer.channels[0].yaw = -33; + + mixer.channels[1].type = MIXER_TYPE_MOTOR; + mixer.channels[1].throttle1 = 100; + mixer.channels[1].throttle2 = 0; + mixer.channels[1].roll = -33; + mixer.channels[1].pitch = 0; + mixer.channels[1].yaw = 33; + + mixer.channels[2].type = MIXER_TYPE_MOTOR; + mixer.channels[2].throttle1 = 100; + mixer.channels[2].throttle2 = 0; + mixer.channels[2].roll = -33; + mixer.channels[2].pitch = -50; + mixer.channels[2].yaw = -33; + + mixer.channels[3].type = MIXER_TYPE_MOTOR; + mixer.channels[3].throttle1 = 100; + mixer.channels[3].throttle2 = 0; + mixer.channels[3].roll = -33; + mixer.channels[3].pitch = -50; + mixer.channels[3].yaw = 33; + + mixer.channels[4].type = MIXER_TYPE_MOTOR; + mixer.channels[4].throttle1 = 100; + mixer.channels[4].throttle2 = 0; + mixer.channels[4].roll = 33; + mixer.channels[4].pitch = 0; + mixer.channels[4].yaw = -33; + + mixer.channels[5].type = MIXER_TYPE_MOTOR; + mixer.channels[5].throttle1 = 100; + mixer.channels[5].throttle2 = 0; + mixer.channels[5].roll = 33; + mixer.channels[5].pitch = 50; + mixer.channels[5].yaw = -33; + + guiSettings.multi.VTOLMotorNE = 1; + guiSettings.multi.VTOLMotorE = 2; + guiSettings.multi.VTOLMotorSE = 3; + guiSettings.multi.VTOLMotorSW = 4; + guiSettings.multi.VTOLMotorW = 5; + guiSettings.multi.VTOLMotorNW = 6; + + break; + } + default: + break; + } + applyMixerConfiguration(mixer); + applyMultiGUISettings(frame, guiSettings); } void VehicleConfigurationHelper::setupOctoCopter() { + mixerSettings mixer; + GUIConfigDataUnion guiSettings = getGUIConfigData(); + SystemSettings::AirframeTypeOptions frame; + + switch(m_configSource->getVehicleSubType()) + { + case VehicleConfigurationSource::MULTI_ROTOR_OCTO: { + frame = SystemSettings::AIRFRAMETYPE_OCTO; + + mixer.channels[0].type = MIXER_TYPE_MOTOR; + mixer.channels[0].throttle1 = 100; + mixer.channels[0].throttle2 = 0; + mixer.channels[0].roll = 0; + mixer.channels[0].pitch = 33; + mixer.channels[0].yaw = -25; + + mixer.channels[1].type = MIXER_TYPE_MOTOR; + mixer.channels[1].throttle1 = 100; + mixer.channels[1].throttle2 = 0; + mixer.channels[1].roll = -33; + mixer.channels[1].pitch = 33; + mixer.channels[1].yaw = 25; + + mixer.channels[2].type = MIXER_TYPE_MOTOR; + mixer.channels[2].throttle1 = 100; + mixer.channels[2].throttle2 = 0; + mixer.channels[2].roll = -33; + mixer.channels[2].pitch = 0; + mixer.channels[2].yaw = -25; + + mixer.channels[3].type = MIXER_TYPE_MOTOR; + mixer.channels[3].throttle1 = 100; + mixer.channels[3].throttle2 = 0; + mixer.channels[3].roll = -33; + mixer.channels[3].pitch = -33; + mixer.channels[3].yaw = 25; + + mixer.channels[4].type = MIXER_TYPE_MOTOR; + mixer.channels[4].throttle1 = 100; + mixer.channels[4].throttle2 = 0; + mixer.channels[4].roll = 0; + mixer.channels[4].pitch = -33; + mixer.channels[4].yaw = -25; + + mixer.channels[5].type = MIXER_TYPE_MOTOR; + mixer.channels[5].throttle1 = 100; + mixer.channels[5].throttle2 = 0; + mixer.channels[5].roll = 33; + mixer.channels[5].pitch = -33; + mixer.channels[5].yaw = 25; + + mixer.channels[6].type = MIXER_TYPE_MOTOR; + mixer.channels[6].throttle1 = 100; + mixer.channels[6].throttle2 = 0; + mixer.channels[6].roll = 33; + mixer.channels[6].pitch = 0; + mixer.channels[6].yaw = -25; + + mixer.channels[7].type = MIXER_TYPE_MOTOR; + mixer.channels[7].throttle1 = 100; + mixer.channels[7].throttle2 = 0; + mixer.channels[7].roll = 33; + mixer.channels[7].pitch = 33; + mixer.channels[7].yaw = 25; + + guiSettings.multi.VTOLMotorN = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorE = 3; + guiSettings.multi.VTOLMotorSE = 4; + guiSettings.multi.VTOLMotorS = 5; + guiSettings.multi.VTOLMotorSW = 6; + guiSettings.multi.VTOLMotorW = 7; + guiSettings.multi.VTOLMotorNW = 8; + + break; + } + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_X: { + frame = SystemSettings::AIRFRAMETYPE_OCTOCOAXX; + + mixer.channels[0].type = MIXER_TYPE_MOTOR; + mixer.channels[0].throttle1 = 100; + mixer.channels[0].throttle2 = 0; + mixer.channels[0].roll = 50; + mixer.channels[0].pitch = 50; + mixer.channels[0].yaw = -50; + + mixer.channels[1].type = MIXER_TYPE_MOTOR; + mixer.channels[1].throttle1 = 100; + mixer.channels[1].throttle2 = 0; + mixer.channels[1].roll = 50; + mixer.channels[1].pitch = 50; + mixer.channels[1].yaw = 50; + + mixer.channels[2].type = MIXER_TYPE_MOTOR; + mixer.channels[2].throttle1 = 100; + mixer.channels[2].throttle2 = 0; + mixer.channels[2].roll = -50; + mixer.channels[2].pitch = 50; + mixer.channels[2].yaw = -50; + + mixer.channels[3].type = MIXER_TYPE_MOTOR; + mixer.channels[3].throttle1 = 100; + mixer.channels[3].throttle2 = 0; + mixer.channels[3].roll = -50; + mixer.channels[3].pitch = 50; + mixer.channels[3].yaw = 50; + + mixer.channels[4].type = MIXER_TYPE_MOTOR; + mixer.channels[4].throttle1 = 100; + mixer.channels[4].throttle2 = 0; + mixer.channels[4].roll = -50; + mixer.channels[4].pitch = -50; + mixer.channels[4].yaw = -50; + + mixer.channels[5].type = MIXER_TYPE_MOTOR; + mixer.channels[5].throttle1 = 100; + mixer.channels[5].throttle2 = 0; + mixer.channels[5].roll = -50; + mixer.channels[5].pitch = -50; + mixer.channels[5].yaw = 50; + + mixer.channels[6].type = MIXER_TYPE_MOTOR; + mixer.channels[6].throttle1 = 100; + mixer.channels[6].throttle2 = 0; + mixer.channels[6].roll = 50; + mixer.channels[6].pitch = -50; + mixer.channels[6].yaw = -50; + + mixer.channels[7].type = MIXER_TYPE_MOTOR; + mixer.channels[7].throttle1 = 100; + mixer.channels[7].throttle2 = 0; + mixer.channels[7].roll = 50; + mixer.channels[7].pitch = -50; + mixer.channels[7].yaw = 50; + + guiSettings.multi.VTOLMotorNW = 1; + guiSettings.multi.VTOLMotorN = 2; + guiSettings.multi.VTOLMotorNE = 3; + guiSettings.multi.VTOLMotorE = 4; + guiSettings.multi.VTOLMotorSE = 5; + guiSettings.multi.VTOLMotorS = 6; + guiSettings.multi.VTOLMotorSW = 7; + guiSettings.multi.VTOLMotorW = 8; + + break; + } + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_COAX_PLUS: { + frame = SystemSettings::AIRFRAMETYPE_OCTOCOAXP; + + mixer.channels[0].type = MIXER_TYPE_MOTOR; + mixer.channels[0].throttle1 = 100; + mixer.channels[0].throttle2 = 0; + mixer.channels[0].roll = 0; + mixer.channels[0].pitch = 100; + mixer.channels[0].yaw = -50; + + mixer.channels[1].type = MIXER_TYPE_MOTOR; + mixer.channels[1].throttle1 = 100; + mixer.channels[1].throttle2 = 0; + mixer.channels[1].roll = 0; + mixer.channels[1].pitch = 100; + mixer.channels[1].yaw = 50; + + mixer.channels[2].type = MIXER_TYPE_MOTOR; + mixer.channels[2].throttle1 = 100; + mixer.channels[2].throttle2 = 0; + mixer.channels[2].roll = -100; + mixer.channels[2].pitch = 0; + mixer.channels[2].yaw = -50; + + mixer.channels[3].type = MIXER_TYPE_MOTOR; + mixer.channels[3].throttle1 = 100; + mixer.channels[3].throttle2 = 0; + mixer.channels[3].roll = -100; + mixer.channels[3].pitch = 0; + mixer.channels[3].yaw = 50; + + mixer.channels[4].type = MIXER_TYPE_MOTOR; + mixer.channels[4].throttle1 = 100; + mixer.channels[4].throttle2 = 0; + mixer.channels[4].roll = 0; + mixer.channels[4].pitch = -100; + mixer.channels[4].yaw = -50; + + mixer.channels[5].type = MIXER_TYPE_MOTOR; + mixer.channels[5].throttle1 = 100; + mixer.channels[5].throttle2 = 0; + mixer.channels[5].roll = 0; + mixer.channels[5].pitch = -100; + mixer.channels[5].yaw = 50; + + mixer.channels[6].type = MIXER_TYPE_MOTOR; + mixer.channels[6].throttle1 = 100; + mixer.channels[6].throttle2 = 0; + mixer.channels[6].roll = 100; + mixer.channels[6].pitch = 0; + mixer.channels[6].yaw = -50; + + mixer.channels[7].type = MIXER_TYPE_MOTOR; + mixer.channels[7].throttle1 = 100; + mixer.channels[7].throttle2 = 0; + mixer.channels[7].roll = 100; + mixer.channels[7].pitch = 0; + mixer.channels[7].yaw = 50; + + guiSettings.multi.VTOLMotorN = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorE = 3; + guiSettings.multi.VTOLMotorSE = 4; + guiSettings.multi.VTOLMotorS = 5; + guiSettings.multi.VTOLMotorSW = 6; + guiSettings.multi.VTOLMotorW = 7; + guiSettings.multi.VTOLMotorNW = 8; + + break; + } + case VehicleConfigurationSource::MULTI_ROTOR_OCTO_V: { + frame = SystemSettings::AIRFRAMETYPE_OCTOV; + mixer.channels[0].type = MIXER_TYPE_MOTOR; + mixer.channels[0].throttle1 = 100; + mixer.channels[0].throttle2 = 0; + mixer.channels[0].roll = -25; + mixer.channels[0].pitch = 8; + mixer.channels[0].yaw = -25; + + mixer.channels[1].type = MIXER_TYPE_MOTOR; + mixer.channels[1].throttle1 = 100; + mixer.channels[1].throttle2 = 0; + mixer.channels[1].roll = -25; + mixer.channels[1].pitch = 25; + mixer.channels[1].yaw = 25; + + mixer.channels[2].type = MIXER_TYPE_MOTOR; + mixer.channels[2].throttle1 = 100; + mixer.channels[2].throttle2 = 0; + mixer.channels[2].roll = -25; + mixer.channels[2].pitch = -25; + mixer.channels[2].yaw = -25; + + mixer.channels[3].type = MIXER_TYPE_MOTOR; + mixer.channels[3].throttle1 = 100; + mixer.channels[3].throttle2 = 0; + mixer.channels[3].roll = -25; + mixer.channels[3].pitch = -8; + mixer.channels[3].yaw = 25; + + mixer.channels[4].type = MIXER_TYPE_MOTOR; + mixer.channels[4].throttle1 = 100; + mixer.channels[4].throttle2 = 0; + mixer.channels[4].roll = 25; + mixer.channels[4].pitch = -8; + mixer.channels[4].yaw = -25; + + mixer.channels[5].type = MIXER_TYPE_MOTOR; + mixer.channels[5].throttle1 = 100; + mixer.channels[5].throttle2 = 0; + mixer.channels[5].roll = 25; + mixer.channels[5].pitch = -25; + mixer.channels[5].yaw = 25; + + mixer.channels[6].type = MIXER_TYPE_MOTOR; + mixer.channels[6].throttle1 = 100; + mixer.channels[6].throttle2 = 0; + mixer.channels[6].roll = 25; + mixer.channels[6].pitch = 25; + mixer.channels[6].yaw = -25; + + mixer.channels[7].type = MIXER_TYPE_MOTOR; + mixer.channels[7].throttle1 = 100; + mixer.channels[7].throttle2 = 0; + mixer.channels[7].roll = 25; + mixer.channels[7].pitch = 8; + mixer.channels[7].yaw = 25; + + guiSettings.multi.VTOLMotorN = 1; + guiSettings.multi.VTOLMotorNE = 2; + guiSettings.multi.VTOLMotorE = 3; + guiSettings.multi.VTOLMotorSE = 4; + guiSettings.multi.VTOLMotorS = 5; + guiSettings.multi.VTOLMotorSW = 6; + guiSettings.multi.VTOLMotorW = 7; + guiSettings.multi.VTOLMotorNW = 8; + + break; + } + default: + break; + } + + applyMixerConfiguration(mixer); + applyMultiGUISettings(frame, guiSettings); }