Browse Source
Realized that I had configured my APM:Plane incorrectly since FlightModeConfig was only set up to work with APM:Copter. Changed code to respect mode switch channel parameter across all APM frame types. Also a pile of other changes to make this code much more bullet proof and correct. Implemented simple mode as well. Changed the style of the code to be more data driven. This allows for adjusting for new param values without needed to changing any code.QGC4.4
3 changed files with 361 additions and 311 deletions
@ -1,307 +1,287 @@ |
|||||||
#include "FlightModeConfig.h" |
/*=====================================================================
|
||||||
|
|
||||||
|
QGroundControl Open Source Ground Control Station |
||||||
|
|
||||||
FlightModeConfig::FlightModeConfig(QWidget *parent) : AP2ConfigWidget(parent) |
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
|
||||||
{ |
|
||||||
ui.setupUi(this); |
|
||||||
connect(ui.savePushButton,SIGNAL(clicked()),this,SLOT(saveButtonClicked())); |
|
||||||
initConnections(); |
|
||||||
} |
|
||||||
|
|
||||||
FlightModeConfig::~FlightModeConfig() |
This file is part of the QGROUNDCONTROL project |
||||||
{ |
|
||||||
} |
|
||||||
void FlightModeConfig::activeUASSet(UASInterface *uas) |
|
||||||
{ |
|
||||||
if (m_uas) |
|
||||||
{ |
|
||||||
disconnect(m_uas,SIGNAL(modeChanged(int,QString,QString)),this,SLOT(modeChanged(int,QString,QString))); |
|
||||||
disconnect(m_uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanged(int,float))); |
|
||||||
} |
|
||||||
AP2ConfigWidget::activeUASSet(uas); |
|
||||||
if (!uas) return; |
|
||||||
connect(m_uas,SIGNAL(modeChanged(int,QString,QString)),this,SLOT(modeChanged(int,QString,QString))); |
|
||||||
connect(m_uas,SIGNAL(remoteControlChannelRawChanged(int,float)),this,SLOT(remoteControlChannelRawChanged(int,float))); |
|
||||||
QStringList itemlist; |
|
||||||
if (m_uas->getSystemType() == MAV_TYPE_FIXED_WING) |
|
||||||
{ |
|
||||||
itemlist << "Manual"; |
|
||||||
itemlist << "Circle"; |
|
||||||
itemlist << "Stabilize"; |
|
||||||
itemlist << "Training"; |
|
||||||
itemlist << "FBW A"; |
|
||||||
itemlist << "FBW B"; |
|
||||||
itemlist << "Auto"; |
|
||||||
itemlist << "RTL"; |
|
||||||
itemlist << "Loiter"; |
|
||||||
itemlist << "Guided"; |
|
||||||
|
|
||||||
planeModeIndexToUiIndex[0] = 0; |
QGROUNDCONTROL is free software: you can redistribute it and/or modify |
||||||
planeModeUiIndexToIndex[0] = 0; |
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. |
||||||
|
|
||||||
planeModeIndexToUiIndex[1] = 1; |
QGROUNDCONTROL is distributed in the hope that it will be useful, |
||||||
planeModeUiIndexToIndex[1] = 1; |
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. |
||||||
|
|
||||||
planeModeIndexToUiIndex[2] = 2; |
You should have received a copy of the GNU General Public License |
||||||
planeModeUiIndexToIndex[2] = 2; |
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
planeModeIndexToUiIndex[3] = 3; |
======================================================================*/ |
||||||
planeModeUiIndexToIndex[3] = 3; |
|
||||||
|
|
||||||
planeModeIndexToUiIndex[5] = 4; |
#include "FlightModeConfig.h" |
||||||
planeModeUiIndexToIndex[4] = 5; |
|
||||||
|
|
||||||
planeModeIndexToUiIndex[6] = 5; |
// We used the _rgModeInfo* arrays to populate the combo box choices. The numeric value
|
||||||
planeModeUiIndexToIndex[5] = 6; |
// is the flight mode value that corresponds to the label. We store that value in the
|
||||||
|
// combo box item data. There is a different set or each vehicle type.
|
||||||
|
|
||||||
planeModeIndexToUiIndex[10] = 6; |
const FlightModeConfig::FlightModeInfo_t FlightModeConfig::_rgModeInfoFixedWing[] = { |
||||||
planeModeUiIndexToIndex[6] = 10; |
{ "Manual", 0 }, |
||||||
|
{ "Circle", 1 }, |
||||||
|
{ "Stabilize", 2 }, |
||||||
|
{ "Training", 3 }, |
||||||
|
{ "FBW A", 5 }, |
||||||
|
{ "FBW B", 6 }, |
||||||
|
{ "Auto", 10 }, |
||||||
|
{ "RTL", 11 }, |
||||||
|
{ "Loiter", 12 }, |
||||||
|
{ "Guided", 15 }, |
||||||
|
}; |
||||||
|
|
||||||
planeModeIndexToUiIndex[11] = 7; |
const FlightModeConfig::FlightModeInfo_t FlightModeConfig::_rgModeInfoRotor[] = { |
||||||
planeModeUiIndexToIndex[7] = 11; |
{ "Stabilize", 0 }, |
||||||
|
{ "Acro", 1 }, |
||||||
|
{ "Alt Hold", 2 }, |
||||||
|
{ "Auto", 3 }, |
||||||
|
{ "Guided", 4 }, |
||||||
|
{ "Loiter", 5 }, |
||||||
|
{ "RTL", 6 }, |
||||||
|
{ "Circle", 7 }, |
||||||
|
{ "Position", 8 }, |
||||||
|
{ "Land", 9 }, |
||||||
|
{ "OF_Loiter", 10 }, |
||||||
|
{ "Toy A", 11 }, |
||||||
|
{ "Toy M", 12 }, |
||||||
|
}; |
||||||
|
|
||||||
planeModeIndexToUiIndex[12] = 8; |
const FlightModeConfig::FlightModeInfo_t FlightModeConfig::_rgModeInfoRover[] = { |
||||||
planeModeUiIndexToIndex[8] = 12; |
{ "Manual", 0 }, |
||||||
|
{ "Learning", 2 }, |
||||||
|
{ "Steering", 3 }, |
||||||
|
{ "Hold", 4 }, |
||||||
|
{ "Auto", 10 }, |
||||||
|
{ "RTL", 11 }, |
||||||
|
{ "Guided", 15 }, |
||||||
|
}; |
||||||
|
|
||||||
planeModeIndexToUiIndex[15] = 9; |
// We use the _rgModeParam* arrays to store the parameter names for each selectable
|
||||||
planeModeUiIndexToIndex[9] = 15; |
// flight mode. The order of these corresponds to the combox box order as well. Array
|
||||||
|
// element 0, is the parameter for mode0ComboBox, array element 1 = mode1ComboBox and
|
||||||
|
// so on. The number of elements in the array also determines how many combo boxes we
|
||||||
|
// are going to need. Different vehicle types have different numbers of selectable
|
||||||
|
// flight modes.
|
||||||
|
|
||||||
ui.mode6ComboBox->setEnabled(true); |
const char* FlightModeConfig::_rgModeParamFixedWing[_cModes] = { "FLTMODE1", "FLTMODE2", "FLTMODE3", "FLTMODE4", "FLTMODE5", "FLTMODE6" }; |
||||||
} |
|
||||||
else if (m_uas->getSystemType() == MAV_TYPE_GROUND_ROVER) |
|
||||||
{ |
|
||||||
itemlist << "Manual"; |
|
||||||
itemlist << "Learning"; |
|
||||||
itemlist << "Steering"; |
|
||||||
itemlist << "Hold"; |
|
||||||
itemlist << "Auto"; |
|
||||||
itemlist << "RTL"; |
|
||||||
itemlist << "Guided"; |
|
||||||
itemlist << "Initialising"; |
|
||||||
ui.mode6ComboBox->setEnabled(false); |
|
||||||
roverModeIndexToUiIndex[0] = 0; |
|
||||||
roverModeUiIndexToIndex[0] = 0; |
|
||||||
|
|
||||||
roverModeIndexToUiIndex[2] = 1; |
const char* FlightModeConfig::_rgModeParamRotor[_cModes] = { "FLTMODE1", "FLTMODE2", "FLTMODE3", "FLTMODE4", "FLTMODE5", "FLTMODE6" }; |
||||||
roverModeUiIndexToIndex[1] = 2; |
|
||||||
|
|
||||||
roverModeIndexToUiIndex[3] = 2; |
const char* FlightModeConfig::_rgModeParamRover[_cModes] = { "MODE1", "MODE2", "MODE3", "MODE4", "MODE5", "MODE6" }; |
||||||
roverModeUiIndexToIndex[2] = 3; |
|
||||||
|
|
||||||
roverModeIndexToUiIndex[4] = 3; |
// Parameter which contains simple mode bitmask
|
||||||
roverModeUiIndexToIndex[3] = 4; |
const char* FlightModeConfig::_simpleModeBitMaskParam = "SIMPLE"; |
||||||
|
|
||||||
roverModeIndexToUiIndex[10] = 5; |
// Parameter which controls which RC channel mode switching is on.
|
||||||
roverModeUiIndexToIndex[5] = 10; |
// ArduCopter is hardcoded so no param
|
||||||
|
const char* FlightModeConfig::_modeSwitchRCChannelParamFixedWing = "FLTMODE_CH"; |
||||||
|
const char* FlightModeConfig::_modeSwitchRCChannelParamRover = "MODE_CH"; |
||||||
|
|
||||||
roverModeIndexToUiIndex[11] = 6; |
// PWM values which are the boundaries between each mode selection
|
||||||
roverModeUiIndexToIndex[6] = 11; |
const int FlightModeConfig::_rgModePWMBoundary[_cModes] = { 1230, 1360, 1490, 1620, 1749, 20000 }; |
||||||
|
|
||||||
roverModeIndexToUiIndex[15] = 7; |
FlightModeConfig::FlightModeConfig(QWidget *parent) : |
||||||
roverModeUiIndexToIndex[7] = 15; |
AP2ConfigWidget(parent), |
||||||
|
_rgModeInfo(NULL), |
||||||
|
_cModeInfo(0), |
||||||
|
_rgModeParam(NULL), |
||||||
|
_simpleModeSupported(false), |
||||||
|
_modeSwitchRCChannel(_modeSwitchRCChannelInvalid) |
||||||
|
{ |
||||||
|
_ui.setupUi(this); |
||||||
|
|
||||||
roverModeIndexToUiIndex[16] = 8; |
// Find all the widgets we are going to programmatically control
|
||||||
roverModeUiIndexToIndex[8] = 16; |
for (size_t i=0; i<_cModes; i++) { |
||||||
|
_rgLabel[i] = findChild<QLabel*>(QString("mode%1Label").arg(i)); |
||||||
|
_rgCombo[i] = findChild<QComboBox*>(QString("mode%1ComboBox").arg(i)); |
||||||
|
_rgSimpleModeCheckBox[i] = findChild<QCheckBox*>(QString("mode%1SimpleCheckBox").arg(i)); |
||||||
|
_rgPWMLabel[i] = findChild<QLabel*>(QString("mode%1PWMLabel").arg(i)); |
||||||
|
Q_ASSERT(_rgLabel[i]); |
||||||
|
Q_ASSERT(_rgCombo[i]); |
||||||
|
Q_ASSERT(_rgSimpleModeCheckBox[i]); |
||||||
|
Q_ASSERT(_rgPWMLabel[i]); |
||||||
|
} |
||||||
|
|
||||||
|
// Start disabled until we get a UAS
|
||||||
|
setEnabled(false); |
||||||
|
|
||||||
} |
connect(_ui.savePushButton, SIGNAL(clicked()), this, SLOT(saveButtonClicked())); |
||||||
else if (m_uas->getSystemType() == MAV_TYPE_QUADROTOR) |
initConnections(); |
||||||
{ |
|
||||||
itemlist << "Stabilize"; |
|
||||||
itemlist << "Acro"; |
|
||||||
itemlist << "Alt Hold"; |
|
||||||
itemlist << "Auto"; |
|
||||||
itemlist << "Guided"; |
|
||||||
itemlist << "Loiter"; |
|
||||||
itemlist << "RTL"; |
|
||||||
itemlist << "Circle"; |
|
||||||
itemlist << "Pos Hold"; |
|
||||||
itemlist << "Land"; |
|
||||||
itemlist << "OF_LOITER"; |
|
||||||
itemlist << "Toy"; |
|
||||||
ui.mode6ComboBox->setEnabled(true); |
|
||||||
} |
|
||||||
ui.mode1ComboBox->addItems(itemlist); |
|
||||||
ui.mode2ComboBox->addItems(itemlist); |
|
||||||
ui.mode3ComboBox->addItems(itemlist); |
|
||||||
ui.mode4ComboBox->addItems(itemlist); |
|
||||||
ui.mode5ComboBox->addItems(itemlist); |
|
||||||
ui.mode6ComboBox->addItems(itemlist); |
|
||||||
} |
|
||||||
void FlightModeConfig::modeChanged(int sysId, QString status, QString description) |
|
||||||
{ |
|
||||||
//Unused?
|
|
||||||
} |
|
||||||
void FlightModeConfig::saveButtonClicked() |
|
||||||
{ |
|
||||||
if (m_uas->getSystemType() == MAV_TYPE_FIXED_WING) |
|
||||||
{ |
|
||||||
m_uas->getParamManager()->setParameter(1,"FLTMODE1",(char)planeModeUiIndexToIndex[ui.mode1ComboBox->currentIndex()]); |
|
||||||
m_uas->getParamManager()->setParameter(1,"FLTMODE2",(char)planeModeUiIndexToIndex[ui.mode2ComboBox->currentIndex()]); |
|
||||||
m_uas->getParamManager()->setParameter(1,"FLTMODE3",(char)planeModeUiIndexToIndex[ui.mode3ComboBox->currentIndex()]); |
|
||||||
m_uas->getParamManager()->setParameter(1,"FLTMODE4",(char)planeModeUiIndexToIndex[ui.mode4ComboBox->currentIndex()]); |
|
||||||
m_uas->getParamManager()->setParameter(1,"FLTMODE5",(char)planeModeUiIndexToIndex[ui.mode5ComboBox->currentIndex()]); |
|
||||||
m_uas->getParamManager()->setParameter(1,"FLTMODE6",(char)planeModeUiIndexToIndex[ui.mode6ComboBox->currentIndex()]); |
|
||||||
} |
|
||||||
else if (m_uas->getSystemType() == MAV_TYPE_GROUND_ROVER) |
|
||||||
{ |
|
||||||
m_uas->getParamManager()->setParameter(1,"MODE1",(char)roverModeUiIndexToIndex[ui.mode1ComboBox->currentIndex()]); |
|
||||||
m_uas->getParamManager()->setParameter(1,"MODE2",(char)roverModeUiIndexToIndex[ui.mode2ComboBox->currentIndex()]); |
|
||||||
m_uas->getParamManager()->setParameter(1,"MODE3",(char)roverModeUiIndexToIndex[ui.mode3ComboBox->currentIndex()]); |
|
||||||
m_uas->getParamManager()->setParameter(1,"MODE4",(char)roverModeUiIndexToIndex[ui.mode4ComboBox->currentIndex()]); |
|
||||||
m_uas->getParamManager()->setParameter(1,"MODE5",(char)roverModeUiIndexToIndex[ui.mode5ComboBox->currentIndex()]); |
|
||||||
} |
|
||||||
else if (m_uas->getSystemType() == MAV_TYPE_QUADROTOR) |
|
||||||
{ |
|
||||||
m_uas->getParamManager()->setParameter(1,"FLTMODE1",(char)ui.mode1ComboBox->currentIndex()); |
|
||||||
m_uas->getParamManager()->setParameter(1,"FLTMODE2",(char)ui.mode2ComboBox->currentIndex()); |
|
||||||
m_uas->getParamManager()->setParameter(1,"FLTMODE3",(char)ui.mode3ComboBox->currentIndex()); |
|
||||||
m_uas->getParamManager()->setParameter(1,"FLTMODE4",(char)ui.mode4ComboBox->currentIndex()); |
|
||||||
m_uas->getParamManager()->setParameter(1,"FLTMODE5",(char)ui.mode5ComboBox->currentIndex()); |
|
||||||
m_uas->getParamManager()->setParameter(1,"FLTMODE6",(char)ui.mode6ComboBox->currentIndex()); |
|
||||||
} |
|
||||||
} |
} |
||||||
|
|
||||||
void FlightModeConfig::remoteControlChannelRawChanged(int chan,float val) |
void FlightModeConfig::activeUASSet(UASInterface *uas) |
||||||
{ |
{ |
||||||
if (chan == 4) |
// Clear the highlighting on PWM labels
|
||||||
{ |
for (size_t i=0; i<_cModes; i++) { |
||||||
//Channel 5 (0 array) is the mode switch.
|
_rgPWMLabel[i]->setStyleSheet(QString("")); |
||||||
///TODO: Make this configurable
|
|
||||||
if (val <= 1230) |
|
||||||
{ |
|
||||||
ui.mode1Label->setStyleSheet("background-color: rgb(0, 255, 0);color: rgb(0, 0, 0);"); |
|
||||||
ui.mode2Label->setStyleSheet(""); |
|
||||||
ui.mode3Label->setStyleSheet(""); |
|
||||||
ui.mode4Label->setStyleSheet(""); |
|
||||||
ui.mode5Label->setStyleSheet(""); |
|
||||||
ui.mode6Label->setStyleSheet(""); |
|
||||||
} |
} |
||||||
else if (val <= 1360) |
|
||||||
{ |
// Disconnect from old UAS
|
||||||
ui.mode1Label->setStyleSheet(""); |
if (m_uas) |
||||||
ui.mode2Label->setStyleSheet("background-color: rgb(0, 255, 0);color: rgb(0, 0, 0);"); |
|
||||||
ui.mode3Label->setStyleSheet(""); |
|
||||||
ui.mode4Label->setStyleSheet(""); |
|
||||||
ui.mode5Label->setStyleSheet(""); |
|
||||||
ui.mode6Label->setStyleSheet(""); |
|
||||||
} |
|
||||||
else if (val <= 1490) |
|
||||||
{ |
{ |
||||||
ui.mode1Label->setStyleSheet(""); |
disconnect(m_uas, SIGNAL(remoteControlChannelRawChanged(int, float)), this, SLOT(remoteControlChannelRawChanged(int, float))); |
||||||
ui.mode2Label->setStyleSheet(""); |
|
||||||
ui.mode3Label->setStyleSheet("background-color: rgb(0, 255, 0);color: rgb(0, 0, 0);"); |
|
||||||
ui.mode4Label->setStyleSheet(""); |
|
||||||
ui.mode5Label->setStyleSheet(""); |
|
||||||
ui.mode6Label->setStyleSheet(""); |
|
||||||
} |
} |
||||||
else if (val <=1620) |
|
||||||
{ |
// Connect to new UAS (if any)
|
||||||
ui.mode1Label->setStyleSheet(""); |
AP2ConfigWidget::activeUASSet(uas); |
||||||
ui.mode2Label->setStyleSheet(""); |
if (!uas) { |
||||||
ui.mode3Label->setStyleSheet(""); |
setEnabled(false); |
||||||
ui.mode4Label->setStyleSheet("background-color: rgb(0, 255, 0);color: rgb(0, 0, 0);"); |
return; |
||||||
ui.mode5Label->setStyleSheet(""); |
|
||||||
ui.mode6Label->setStyleSheet(""); |
|
||||||
} |
} |
||||||
else if (val <=1749) |
connect(m_uas, SIGNAL(remoteControlChannelRawChanged(int, float)), this, SLOT(remoteControlChannelRawChanged(int, float))); |
||||||
{ |
setEnabled(true); |
||||||
ui.mode1Label->setStyleSheet(""); |
|
||||||
ui.mode2Label->setStyleSheet(""); |
// Select the correct set of Flight Modes and Flight Mode Parameters. If the rc channel
|
||||||
ui.mode3Label->setStyleSheet(""); |
// associated with the mode switch is settable through a param, it is invalid until
|
||||||
ui.mode4Label->setStyleSheet(""); |
// we get that param through.
|
||||||
ui.mode5Label->setStyleSheet("background-color: rgb(0, 255, 0);color: rgb(0, 0, 0);"); |
switch (m_uas->getSystemType()) { |
||||||
ui.mode6Label->setStyleSheet(""); |
case MAV_TYPE_FIXED_WING: |
||||||
|
_rgModeInfo = &_rgModeInfoFixedWing[0]; |
||||||
|
_cModeInfo = sizeof(_rgModeInfoFixedWing)/sizeof(_rgModeInfoFixedWing[0]); |
||||||
|
_rgModeParam = _rgModeParamFixedWing; |
||||||
|
_simpleModeSupported = false; |
||||||
|
_modeSwitchRCChannelParam = _modeSwitchRCChannelParamFixedWing; |
||||||
|
_modeSwitchRCChannel = _modeSwitchRCChannelInvalid; |
||||||
|
break; |
||||||
|
case MAV_TYPE_GROUND_ROVER: |
||||||
|
_rgModeInfo = &_rgModeInfoRover[0]; |
||||||
|
_cModeInfo = sizeof(_rgModeInfoRover)/sizeof(_rgModeInfoRover[0]); |
||||||
|
_rgModeParam = _rgModeParamRover; |
||||||
|
_simpleModeSupported = false; |
||||||
|
_modeSwitchRCChannelParam = _modeSwitchRCChannelParamRover; |
||||||
|
_modeSwitchRCChannel = _modeSwitchRCChannelInvalid; |
||||||
|
break; |
||||||
|
case MAV_TYPE_QUADROTOR: |
||||||
|
case MAV_TYPE_TRICOPTER: |
||||||
|
case MAV_TYPE_HEXAROTOR: |
||||||
|
case MAV_TYPE_OCTOROTOR: |
||||||
|
case MAV_TYPE_HELICOPTER: |
||||||
|
_rgModeInfo = &_rgModeInfoRotor[0]; |
||||||
|
_cModeInfo = sizeof(_rgModeInfoRotor)/sizeof(_rgModeInfoRotor[0]); |
||||||
|
_rgModeParam = _rgModeParamRotor; |
||||||
|
_simpleModeSupported = true; |
||||||
|
_modeSwitchRCChannelParam = NULL; |
||||||
|
_modeSwitchRCChannel = _modeSwitchRCChannelRotor; // Rotor is harcoded
|
||||||
|
break; |
||||||
|
default: |
||||||
|
// We've gotten a mav type we can't handle, just disable to whole thing
|
||||||
|
qDebug() << QString("Unknown System Type %1").arg(m_uas->getSystemType()); |
||||||
|
setEnabled(false); |
||||||
|
return; |
||||||
} |
} |
||||||
else |
|
||||||
{ |
// Set up the combo boxes
|
||||||
ui.mode1Label->setStyleSheet(""); |
for (size_t i=0; i<_cModes; i++) { |
||||||
ui.mode2Label->setStyleSheet(""); |
// Fill each combo box with the available flight modes
|
||||||
ui.mode3Label->setStyleSheet(""); |
for (size_t j=0; j<_cModeInfo; j++) { |
||||||
ui.mode4Label->setStyleSheet(""); |
_rgCombo[i]->addItem(_rgModeInfo[j].label, QVariant(QChar((char)_rgModeInfo[j].value))); |
||||||
ui.mode5Label->setStyleSheet(""); |
|
||||||
ui.mode6Label->setStyleSheet("background-color: rgb(0, 255, 0);color: rgb(0, 0, 0);"); |
|
||||||
} |
} |
||||||
|
|
||||||
|
// Not all vehicle types support simple mode, hide/show as appropriate
|
||||||
|
_rgSimpleModeCheckBox[i]->setEnabled(_simpleModeSupported); |
||||||
} |
} |
||||||
} |
} |
||||||
|
|
||||||
void FlightModeConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) |
void FlightModeConfig::saveButtonClicked(void) |
||||||
{ |
{ |
||||||
if (m_uas->getSystemType() == MAV_TYPE_FIXED_WING) |
// Save the current setting for each flight mode slot
|
||||||
{ |
for (size_t i=0; i<_cModes; i++) { |
||||||
if (parameterName == "FLTMODE1") |
m_uas->getParamManager()->setParameter(1, _rgModeParam[i], _rgCombo[i]->itemData(_rgCombo[i]->currentIndex())); |
||||||
{ |
QVariant var =_rgCombo[i]->itemData(_rgCombo[i]->currentIndex()); |
||||||
ui.mode1ComboBox->setCurrentIndex(planeModeIndexToUiIndex[value.toInt()]); |
|
||||||
} |
|
||||||
else if (parameterName == "FLTMODE2") |
|
||||||
{ |
|
||||||
ui.mode2ComboBox->setCurrentIndex(planeModeIndexToUiIndex[value.toInt()]); |
|
||||||
} |
|
||||||
else if (parameterName == "FLTMODE3") |
|
||||||
{ |
|
||||||
ui.mode3ComboBox->setCurrentIndex(planeModeIndexToUiIndex[value.toInt()]); |
|
||||||
} |
|
||||||
else if (parameterName == "FLTMODE4") |
|
||||||
{ |
|
||||||
ui.mode4ComboBox->setCurrentIndex(planeModeIndexToUiIndex[value.toInt()]); |
|
||||||
} |
|
||||||
else if (parameterName == "FLTMODE5") |
|
||||||
{ |
|
||||||
ui.mode5ComboBox->setCurrentIndex(planeModeIndexToUiIndex[value.toInt()]); |
|
||||||
} |
|
||||||
else if (parameterName == "FLTMODE6") |
|
||||||
{ |
|
||||||
ui.mode6ComboBox->setCurrentIndex(planeModeIndexToUiIndex[value.toInt()]); |
|
||||||
} |
} |
||||||
|
|
||||||
|
// Save Simple Mode bit mask if supported
|
||||||
|
if (_simpleModeSupported) { |
||||||
|
int bitMask = 0; |
||||||
|
for (size_t i=0; i<_cModes; i++) { |
||||||
|
if (_rgSimpleModeCheckBox[i]->isChecked()) { |
||||||
|
bitMask |= 1 << i; |
||||||
} |
} |
||||||
else if (m_uas->getSystemType() == MAV_TYPE_GROUND_ROVER) |
|
||||||
{ |
|
||||||
if (parameterName == "MODE1") |
|
||||||
{ |
|
||||||
ui.mode1ComboBox->setCurrentIndex(roverModeIndexToUiIndex[value.toInt()]); |
|
||||||
} |
} |
||||||
else if (parameterName == "MODE2") |
m_uas->getParamManager()->setParameter(1, _simpleModeBitMaskParam, QVariant(QChar(bitMask))); |
||||||
{ |
|
||||||
ui.mode2ComboBox->setCurrentIndex(roverModeIndexToUiIndex[value.toInt()]); |
|
||||||
} |
} |
||||||
else if (parameterName == "MODE3") |
} |
||||||
{ |
|
||||||
ui.mode3ComboBox->setCurrentIndex(roverModeIndexToUiIndex[value.toInt()]); |
// Higlights the PWM label for currently selected mode according the mode switch
|
||||||
} |
// rc channel value.
|
||||||
else if (parameterName == "MODE4") |
void FlightModeConfig::remoteControlChannelRawChanged(int chan, float val) |
||||||
|
{ |
||||||
|
qDebug() << chan << val << _modeSwitchRCChannel; |
||||||
|
// Until we get the _modeSwitchRCChannel value from a parameter it will be set
|
||||||
|
// to -1, which is an invalid channel thus the labels won't update
|
||||||
|
if (chan == _modeSwitchRCChannel) |
||||||
{ |
{ |
||||||
ui.mode4ComboBox->setCurrentIndex(roverModeIndexToUiIndex[value.toInt()]); |
qDebug() << chan << val; |
||||||
|
size_t highlightIndex; |
||||||
|
|
||||||
|
for (size_t i=0; i<_cModes; i++) { |
||||||
|
if (val < _rgModePWMBoundary[i]) { |
||||||
|
highlightIndex = i; |
||||||
|
break; |
||||||
} |
} |
||||||
else if (parameterName == "MODE5") |
|
||||||
{ |
|
||||||
ui.mode5ComboBox->setCurrentIndex(roverModeIndexToUiIndex[value.toInt()]); |
|
||||||
} |
} |
||||||
|
|
||||||
|
for (size_t i=0; i<_cModes; i++) { |
||||||
|
QString styleSheet; |
||||||
|
if (i == highlightIndex) { |
||||||
|
styleSheet = "background-color: rgb(0, 255, 0);color: rgb(0, 0, 0);"; |
||||||
|
} else { |
||||||
|
styleSheet = ""; |
||||||
} |
} |
||||||
else if (m_uas->getSystemType() == MAV_TYPE_QUADROTOR) |
_rgPWMLabel[i]->setStyleSheet(styleSheet); |
||||||
{ |
|
||||||
if (parameterName == "FLTMODE1") |
|
||||||
{ |
|
||||||
ui.mode1ComboBox->setCurrentIndex(value.toInt()); |
|
||||||
} |
} |
||||||
else if (parameterName == "FLTMODE2") |
|
||||||
{ |
|
||||||
ui.mode2ComboBox->setCurrentIndex(value.toInt()); |
|
||||||
} |
} |
||||||
else if (parameterName == "FLTMODE3") |
} |
||||||
{ |
|
||||||
ui.mode3ComboBox->setCurrentIndex(value.toInt()); |
void FlightModeConfig::parameterChanged(int uas, int component, QString parameterName, QVariant value) |
||||||
|
{ |
||||||
|
Q_UNUSED(uas); |
||||||
|
Q_UNUSED(component); |
||||||
|
|
||||||
|
int iValue = value.toInt(); |
||||||
|
|
||||||
|
if (parameterName == _modeSwitchRCChannelParam) { |
||||||
|
_modeSwitchRCChannel = iValue - 1; // 1-based in params
|
||||||
|
} else if (parameterName == _simpleModeBitMaskParam) { |
||||||
|
if (_simpleModeSupported) { |
||||||
|
for (size_t i=0; i<_cModes; i++) { |
||||||
|
_rgSimpleModeCheckBox[i]->setCheckState((iValue & (1 << i)) ? Qt::Checked : Qt::Unchecked); |
||||||
|
} |
||||||
|
} else { |
||||||
|
qDebug() << "Received simple mode parameter on non simple mode vehicle type"; |
||||||
|
} |
||||||
|
} else { |
||||||
|
// Loop over the flight mode params looking for a match
|
||||||
|
for (size_t i=0; i<_cModes; i++) { |
||||||
|
if (parameterName == _rgModeParam[i]) { |
||||||
|
// We found a match, i is now the index of the combo box which displays that mode slot
|
||||||
|
// Loop over the mode info till we find the matching value, this tells us which row in the
|
||||||
|
// combo box to select.
|
||||||
|
QComboBox* combo = _rgCombo[i]; |
||||||
|
for (size_t j=0; j<_cModeInfo; j++) { |
||||||
|
if (_rgModeInfo[j].value == iValue) { |
||||||
|
combo->setCurrentIndex(j); |
||||||
|
return; |
||||||
} |
} |
||||||
else if (parameterName == "FLTMODE4") |
|
||||||
{ |
|
||||||
ui.mode4ComboBox->setCurrentIndex(value.toInt()); |
|
||||||
} |
} |
||||||
else if (parameterName == "FLTMODE5") |
|
||||||
{ |
// We should have been able to find the flight mode value. If we didn't, we have been passed a
|
||||||
ui.mode5ComboBox->setCurrentIndex(value.toInt()); |
// flight mode that we don't understand. Possibly a newer firmware version we are not yet up
|
||||||
|
// to date with. In this case, add a new item to the combo box to represent it.
|
||||||
|
qDebug() << QString("Unknown flight mode value %1").arg(iValue); |
||||||
|
combo->addItem(QString("%1 - Unknown").arg(iValue), QVariant(iValue)); |
||||||
|
combo->setCurrentIndex(combo->count() - 1); |
||||||
} |
} |
||||||
else if (parameterName == "FLTMODE6") |
|
||||||
{ |
|
||||||
ui.mode6ComboBox->setCurrentIndex(value.toInt()); |
|
||||||
} |
} |
||||||
} |
} |
||||||
} |
} |
||||||
|
Loading…
Reference in new issue