Commit 657c11d9 authored by Don Gagne's avatar Don Gagne

Merge pull request #2963 from DonLakeFlyer/APMFlightMode

Fix settable flight mode channel
parents 76975530 9868e0d5
...@@ -39,6 +39,9 @@ QGCView { ...@@ -39,6 +39,9 @@ QGCView {
property bool _channel7OptionsAvailable: controller.parameterExists(-1, "CH7_OPT") // Not available in all firmware types property bool _channel7OptionsAvailable: controller.parameterExists(-1, "CH7_OPT") // Not available in all firmware types
property bool _channel9OptionsAvailable: controller.parameterExists(-1, "CH9_OPT") // Not available in all firmware types property bool _channel9OptionsAvailable: controller.parameterExists(-1, "CH9_OPT") // Not available in all firmware types
property int _channelOptionCount: _channel7OptionsAvailable ? (_channel9OptionsAvailable ? 6 : 2) : 0 property int _channelOptionCount: _channel7OptionsAvailable ? (_channel9OptionsAvailable ? 6 : 2) : 0
property Fact _nullFact
property bool _fltmodeChExists: controller.parameterExists(-1, "FLTMODE_CH")
property Fact _fltmodeCh: _fltmodeChExists ? controller.getParameterFact(-1, "FLTMODE_CH") : _nullFact
QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled } QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled }
...@@ -59,7 +62,7 @@ QGCView { ...@@ -59,7 +62,7 @@ QGCView {
QGCLabel { QGCLabel {
id: flightModeLabel id: flightModeLabel
text: "Channel 5 Flight Mode Settings" text: "Flight Mode Settings" + (_fltmodeChExists ? "" : " (Channel 5)")
font.weight: Font.DemiBold font.weight: Font.DemiBold
} }
...@@ -75,10 +78,28 @@ QGCView { ...@@ -75,10 +78,28 @@ QGCView {
id: flightModeColumn id: flightModeColumn
anchors.margins: ScreenTools.defaultFontPixelWidth anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left anchors.left: parent.left
// anchors.right: parent.right
anchors.top: parent.top anchors.top: parent.top
spacing: ScreenTools.defaultFontPixelHeight spacing: ScreenTools.defaultFontPixelHeight
Row {
spacing: _margins
visible: _fltmodeChExists
QGCLabel {
id: modeChannelLabel
anchors.baseline: modeChannelCombo.baseline
text: "Flight mode channel:"
}
QGCComboBox {
id: modeChannelCombo
width: ScreenTools.defaultFontPixelWidth * 15
model: [ "Not assigned", "Channel 1", "Channel 2","Channel 3","Channel 4","Channel 5","Channel 6","Channel 7","Channel 8" ]
currentIndex: _fltmodeCh.value
onActivated: _fltmodeCh.value = index
}
}
Repeater { Repeater {
model: 6 model: 6
......
...@@ -32,8 +32,6 @@ APMFlightModesComponentController::APMFlightModesComponentController(void) ...@@ -32,8 +32,6 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
: _activeFlightMode(0) : _activeFlightMode(0)
, _channelCount(Vehicle::cMaxRcChannels) , _channelCount(Vehicle::cMaxRcChannels)
, _fixedWing(_vehicle->vehicleType() == MAV_TYPE_FIXED_WING) , _fixedWing(_vehicle->vehicleType() == MAV_TYPE_FIXED_WING)
, _flightModeChannel(5)
{ {
QStringList usedParams; QStringList usedParams;
usedParams << QStringLiteral("FLTMODE1") << QStringLiteral("FLTMODE2") << QStringLiteral("FLTMODE3") usedParams << QStringLiteral("FLTMODE1") << QStringLiteral("FLTMODE2") << QStringLiteral("FLTMODE3")
...@@ -42,10 +40,6 @@ APMFlightModesComponentController::APMFlightModesComponentController(void) ...@@ -42,10 +40,6 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
return; return;
} }
if (parameterExists(FactSystem::defaultComponentId, QStringLiteral("FLTMODE_CH"))) {
_flightModeChannel = getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FLTMODE_CH"))->rawValue().toInt();
}
_rgChannelOptionEnabled << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false); _rgChannelOptionEnabled << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false);
connect(_vehicle, &Vehicle::rcChannelsChanged, this, &APMFlightModesComponentController::_rcChannelsChanged); connect(_vehicle, &Vehicle::rcChannelsChanged, this, &APMFlightModesComponentController::_rcChannelsChanged);
...@@ -54,12 +48,18 @@ APMFlightModesComponentController::APMFlightModesComponentController(void) ...@@ -54,12 +48,18 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
/// Connected to Vehicle::rcChannelsChanged signal /// Connected to Vehicle::rcChannelsChanged signal
void APMFlightModesComponentController::_rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels]) void APMFlightModesComponentController::_rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels])
{ {
if (_flightModeChannel > channelCount) { int flightModeChannel = 4;
if (parameterExists(FactSystem::defaultComponentId, QStringLiteral("FLTMODE_CH"))) {
flightModeChannel = getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FLTMODE_CH"))->rawValue().toInt() - 1;
}
if (flightModeChannel >= channelCount) {
return; return;
} }
_activeFlightMode = 0; _activeFlightMode = 0;
int channelValue = pwmValues[_flightModeChannel - 1]; int channelValue = pwmValues[flightModeChannel];
if (channelValue != -1) { if (channelValue != -1) {
bool found = false; bool found = false;
int rgThreshold[] = { 1230, 1360, 1490, 1620, 1749 }; int rgThreshold[] = { 1230, 1360, 1490, 1620, 1749 };
......
...@@ -62,7 +62,6 @@ private: ...@@ -62,7 +62,6 @@ private:
int _channelCount; int _channelCount;
QVariantList _rgChannelOptionEnabled; QVariantList _rgChannelOptionEnabled;
bool _fixedWing; bool _fixedWing;
int _flightModeChannel;
}; };
#endif #endif
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