Commit f90d1b98 authored by DonLakeFlyer's avatar DonLakeFlyer

parent 4224b476
...@@ -150,7 +150,7 @@ SetupPage { ...@@ -150,7 +150,7 @@ SetupPage {
Layout.alignment: Qt.AlignHCenter Layout.alignment: Qt.AlignHCenter
visible: _customSimpleMode visible: _customSimpleMode
checked: modelData checked: modelData
onClicked: controller.setSimpleMode(index, checked) onClicked: controller.setSuperSimpleMode(index, checked)
} }
} }
...@@ -166,7 +166,7 @@ SetupPage { ...@@ -166,7 +166,7 @@ SetupPage {
spacing: _margins spacing: _margins
visible: controller.simpleModesSupported visible: controller.simpleModesSupported
QGCLabel { text: qsTr("Set All Flight Modes To") } QGCLabel { text: qsTr("Simple Mode") }
QGCComboBox { QGCComboBox {
model: controller.simpleModeNames model: controller.simpleModeNames
......
...@@ -39,13 +39,7 @@ APMFlightModesComponentController::APMFlightModesComponentController(void) ...@@ -39,13 +39,7 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
} }
if (!_rover) { if (!_rover) {
for (int i=0; i<_cFltModes; i++) { _setupSimpleModeEnabled();
Fact* fltModeFact = getParameterFact(-1, QStringLiteral("%1%2").arg(_modeParamPrefix).arg(i+1));
_rgFltModeFacts.append(fltModeFact);
connect(fltModeFact, &Fact::rawValueChanged, this, &APMFlightModesComponentController::_adjustSimpleModeEnabledFromParams);
}
_adjustSimpleModeEnabledFromParams();
uint8_t simpleModeValue = static_cast<uint8_t>(_simpleModeFact->rawValue().toUInt()); uint8_t simpleModeValue = static_cast<uint8_t>(_simpleModeFact->rawValue().toUInt());
uint8_t superSimpleModeValue = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toUInt()); uint8_t superSimpleModeValue = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toUInt());
...@@ -59,9 +53,7 @@ APMFlightModesComponentController::APMFlightModesComponentController(void) ...@@ -59,9 +53,7 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
_simpleMode = SimpleModeCustom; _simpleMode = SimpleModeCustom;
} }
connect(this, &APMFlightModesComponentController::simpleModeChanged, this, &APMFlightModesComponentController::_updateSimpleParamsFromSimpleMode); connect(this, &APMFlightModesComponentController::simpleModeChanged, this, &APMFlightModesComponentController::_updateSimpleParamsFromSimpleMode);
connect(_simpleModeFact, &Fact::rawValueChanged, this, &APMFlightModesComponentController::_adjustSimpleModeEnabledFromParams);
connect(_superSimpleModeFact, &Fact::rawValueChanged, this, &APMFlightModesComponentController::_adjustSimpleModeEnabledFromParams);
} }
QStringList usedParams; QStringList usedParams;
...@@ -131,6 +123,13 @@ void APMFlightModesComponentController::_updateSimpleParamsFromSimpleMode(void) ...@@ -131,6 +123,13 @@ void APMFlightModesComponentController::_updateSimpleParamsFromSimpleMode(void)
newSuperSimpleModeValue = _allSimpleBits; newSuperSimpleModeValue = _allSimpleBits;
} }
for (int i=0; i<_cFltModes; i++) {
_simpleModeEnabled[i] = false;
_superSimpleModeEnabled[i] = false;
}
emit simpleModeEnabledChanged();
emit superSimpleModeEnabledChanged();
_simpleModeFact->setRawValue(newSimpleModeValue); _simpleModeFact->setRawValue(newSimpleModeValue);
_superSimpleModeFact->setRawValue(newSuperSimpleModeValue); _superSimpleModeFact->setRawValue(newSuperSimpleModeValue);
} }
...@@ -138,58 +137,38 @@ void APMFlightModesComponentController::_updateSimpleParamsFromSimpleMode(void) ...@@ -138,58 +137,38 @@ void APMFlightModesComponentController::_updateSimpleParamsFromSimpleMode(void)
void APMFlightModesComponentController::setSimpleMode(int fltModeIndex, bool enabled) void APMFlightModesComponentController::setSimpleMode(int fltModeIndex, bool enabled)
{ {
if (fltModeIndex < _cFltModes) { if (fltModeIndex < _cFltModes) {
int fltMode = _rgFltModeFacts[fltModeIndex]->rawValue().toInt(); uint8_t mode = static_cast<uint8_t>(_simpleModeFact->rawValue().toInt());
if (fltMode < _cSimpleModeBits) { if (enabled) {
uint8_t mode = static_cast<uint8_t>(_simpleModeFact->rawValue().toInt()); mode |= 1 << fltModeIndex;
if (enabled) { } else {
mode |= 1 << fltMode; mode &= ~(1 << fltModeIndex);
} else {
mode &= ~(1 << fltMode);
}
_simpleModeFact->setRawValue(mode);
} }
_simpleModeFact->setRawValue(mode);
} }
} }
void APMFlightModesComponentController::setSuperSimpleMode(int fltModeIndex, bool enabled) void APMFlightModesComponentController::setSuperSimpleMode(int fltModeIndex, bool enabled)
{ {
if (fltModeIndex < _cFltModes) { if (fltModeIndex < _cFltModes) {
int fltMode = _rgFltModeFacts[fltModeIndex]->rawValue().toInt(); uint8_t mode = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toInt());
if (fltMode < _cSimpleModeBits) { if (enabled) {
uint8_t mode = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toInt()); mode |= 1 << fltModeIndex;
if (enabled) { } else {
mode |= 1 << fltMode; mode &= ~(1 << fltModeIndex);
} else {
mode &= ~(1 << fltMode);
}
_superSimpleModeFact->setRawValue(mode);
} }
_superSimpleModeFact->setRawValue(mode);
} }
} }
void APMFlightModesComponentController::_adjustSimpleModeEnabledFromParams(void) void APMFlightModesComponentController::_setupSimpleModeEnabled(void)
{ {
uint8_t simpleMode = static_cast<uint8_t>(_simpleModeFact->rawValue().toUInt()); uint8_t simpleMode = static_cast<uint8_t>(_simpleModeFact->rawValue().toUInt());
uint8_t superSimpleMode = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toUInt()); uint8_t superSimpleMode = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toUInt());
for (int fltModeIndex=0; fltModeIndex<_cFltModes; fltModeIndex++) { for (int i=0; i<_cFltModes; i++) {
_simpleModeEnabled[fltModeIndex] = false; uint8_t bitSet = static_cast<uint8_t>(1 << i);
_superSimpleModeEnabled[fltModeIndex] = false; _simpleModeEnabled[i] = !!(simpleMode & bitSet);
} _superSimpleModeEnabled[i] = !!(superSimpleMode & bitSet);
for (int fltModeBit=0; fltModeBit<_cSimpleModeBits; fltModeBit++) {
for (int fltModeIndex=0; fltModeIndex<_cFltModes; fltModeIndex++) {
int fltModeValue = _rgFltModeFacts[fltModeIndex]->rawValue().toInt();
uint8_t bitSet = 1 << fltModeBit;
bool simpleModeBitEnabled = !!(simpleMode & bitSet) && fltModeValue == fltModeBit;
bool superSimpleModeBitEnabled = !!(superSimpleMode & bitSet) && fltModeValue == fltModeBit;
if (simpleModeBitEnabled) {
_simpleModeEnabled[fltModeIndex] = true;
}
if (superSimpleModeBitEnabled) {
_superSimpleModeEnabled[fltModeIndex] = true;
}
}
} }
emit simpleModeEnabledChanged(); emit simpleModeEnabledChanged();
......
...@@ -64,7 +64,7 @@ signals: ...@@ -64,7 +64,7 @@ signals:
private slots: private slots:
void _rcChannelsChanged (int channelCount, int pwmValues[Vehicle::cMaxRcChannels]); void _rcChannelsChanged (int channelCount, int pwmValues[Vehicle::cMaxRcChannels]);
void _updateSimpleParamsFromSimpleMode (void); void _updateSimpleParamsFromSimpleMode (void);
void _adjustSimpleModeEnabledFromParams (void); void _setupSimpleModeEnabled (void);
private: private:
bool _rover; bool _rover;
...@@ -75,7 +75,6 @@ private: ...@@ -75,7 +75,6 @@ private:
QVariantList _rgChannelOptionEnabled; QVariantList _rgChannelOptionEnabled;
QStringList _simpleModeNames; QStringList _simpleModeNames;
int _simpleMode; int _simpleMode;
QList<Fact*> _rgFltModeFacts;
Fact* _simpleModeFact; Fact* _simpleModeFact;
Fact* _superSimpleModeFact; Fact* _superSimpleModeFact;
bool _simpleModesSupported; bool _simpleModesSupported;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment