Unverified Commit 2cc55e0a authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7417 from DonLakeFlyer/SimpleFlightModes

ArduPilot: Simple flight modes
parents d6ad774b d3ef1500
......@@ -6,6 +6,8 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build
* ArduPilot: Copter - Add suppor for Simple and Super Simple flight modes
* ArduPilot: Flight Mode setup - Switch Options were not showing up for all firmware revs
* ArduCopter: Add PID Tuning page to Tuning Setup
* ArduPilot: Copter - Advanced Tuning support
* ArduPilot: Rover - Frame setup support
......
......@@ -8,8 +8,9 @@
****************************************************************************/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Layouts 1.2
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
......@@ -24,14 +25,16 @@ SetupPage {
readonly property string _modeChannelParam: controller.modeChannelParam
readonly property string _modeParamPrefix: controller.modeParamPrefix
readonly property var _pwmStrings: [ "PWM 0 - 1230", "PWM 1231 - 1360", "PWM 1361 - 1490", "PWM 1491 - 1620", "PWM 1621 - 1749", "PWM 1750 +"]
property real _margins: ScreenTools.defaultFontPixelHeight
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 int _channelOptionCount: _channel7OptionsAvailable ? (_channel9OptionsAvailable ? 6 : 2) : 0
property Fact _nullFact
property bool _fltmodeChExists: controller.parameterExists(-1, _modeChannelParam)
property Fact _fltmodeCh: _fltmodeChExists ? controller.getParameterFact(-1, _modeChannelParam) : _nullFact
property bool _ch7OptAvailable: controller.parameterExists(-1, "CH7_OPT")
property int _rcOptionStart: _ch7OptAvailable ? 7 : 6
property int _rcOptionStop: _ch7OptAvailable ? 12 : 16
property bool _customSimpleMode: controller.simpleMode === APMFlightModesComponentController.SimpleModeCustom
QGCPalette { id: qgcPal; colorGroupEnabled: true }
......@@ -43,136 +46,186 @@ SetupPage {
Component {
id: flightModePageComponent
Flow {
id: flowLayout
width: availableWidth
spacing: _margins
Column {
spacing: _margins
QGCLabel {
id: flightModeLabel
text: qsTr("Flight Mode Settings") + (_fltmodeChExists ? "" : qsTr(" (Channel 5)"))
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
id: flightModeSettings
width: flightModeColumn.width + (_margins * 2)
height: flightModeColumn.height + ScreenTools.defaultFontPixelHeight
color: qgcPal.windowShade
Column {
id: flightModeColumn
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
anchors.top: parent.top
spacing: ScreenTools.defaultFontPixelHeight
Flow {
id: flowLayout
width: availableWidth
spacing: _margins
Column {
spacing: _margins
QGCLabel {
id: flightModeLabel
text: qsTr("Flight Mode Settings") + (_fltmodeChExists ? "" : qsTr(" (Channel 5)"))
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
id: flightModeSettings
width: flightModeColumn.width + (_margins * 2)
height: flightModeColumn.height + ScreenTools.defaultFontPixelHeight
color: qgcPal.windowShade
Column {
id: flightModeColumn
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
anchors.top: parent.top
spacing: ScreenTools.defaultFontPixelHeight
Row {
spacing: _margins
visible: _fltmodeChExists
QGCLabel {
id: modeChannelLabel
anchors.baseline: modeChannelCombo.baseline
text: qsTr("Flight mode channel:")
}
Row {
spacing: _margins
visible: _fltmodeChExists
QGCComboBox {
id: modeChannelCombo
width: ScreenTools.defaultFontPixelWidth * 15
model: [ qsTr("Not assigned"), qsTr("Channel 1"), qsTr("Channel 2"),
qsTr("Channel 3"), qsTr("Channel 4"), qsTr("Channel 5"),
qsTr("Channel 6"), qsTr("Channel 7"), qsTr("Channel 8") ]
currentIndex: _fltmodeCh.value
onActivated: _fltmodeCh.value = index
}
}
GridLayout {
rows: _customSimpleMode ? 7 : 6
flow: GridLayout.TopToBottom
QGCLabel { text: ""; visible: _customSimpleMode }
Repeater {
model: 6
QGCLabel {
id: modeChannelLabel
anchors.baseline: modeChannelCombo.baseline
text: qsTr("Flight mode channel:")
text: qsTr("Flight Mode ") + index
color: controller.activeFlightMode == index ? "yellow" : qgcPal.text
property int index: modelData + 1
}
}
QGCComboBox {
id: modeChannelCombo
width: ScreenTools.defaultFontPixelWidth * 15
model: [ qsTr("Not assigned"), qsTr("Channel 1"), qsTr("Channel 2"),
qsTr("Channel 3"), qsTr("Channel 4"), qsTr("Channel 5"),
qsTr("Channel 6"), qsTr("Channel 7"), qsTr("Channel 8") ]
QGCLabel { text: ""; visible: _customSimpleMode }
Repeater {
model: 6
currentIndex: _fltmodeCh.value
onActivated: _fltmodeCh.value = index
FactComboBox {
Layout.preferredWidth: ScreenTools.defaultFontPixelWidth * 15
fact: controller.getParameterFact(-1, _modeParamPrefix + index)
indexModel: false
property int index: modelData + 1
}
}
QGCLabel {
text: qsTr("Simple")
font.pointSize: ScreenTools.smallFontPointSize
visible: _customSimpleMode
}
Repeater {
model: 6
model: controller.simpleModeEnabled
QGCCheckBox {
Layout.alignment: Qt.AlignHCenter
visible: _customSimpleMode
checked: modelData
onClicked: controller.setSimpleMode(index, checked)
}
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
property int index: modelData + 1
property var pwmStrings: [ "PWM 0 - 1230", "PWM 1231 - 1360", "PWM 1361 - 1490", "PWM 1491 - 1620", "PWM 1621 - 1749", "PWM 1750 +"]
QGCLabel {
anchors.baseline: modeCombo.baseline
text: qsTr("Flight Mode ") + index + ":"
color: controller.activeFlightMode == index ? "yellow" : qgcPal.text
}
FactComboBox {
id: modeCombo
width: ScreenTools.defaultFontPixelWidth * 15
fact: controller.getParameterFact(-1, _modeParamPrefix + index)
indexModel: false
}
QGCLabel {
anchors.baseline: modeCombo.baseline
text: pwmStrings[modelData]
}
QGCLabel {
text: qsTr("Super-Simple")
font.pointSize: ScreenTools.smallFontPointSize
visible: _customSimpleMode
}
Repeater {
model: controller.superSimpleModeEnabled
QGCCheckBox {
Layout.alignment: Qt.AlignHCenter
visible: _customSimpleMode
checked: modelData
onClicked: controller.setSuperSimpleMode(index, checked)
}
} // Repeater - Flight Modes
} // Column - Flight Modes
} // Rectangle - Flight Modes
} // Column - Flight Modes
Column {
spacing: _margins
visible: _channelOptionCount != 0
QGCLabel {
id: channelOptionsLabel
text: qsTr("Channel Options")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
id: channelOptionsSettings
width: channelOptColumn.width + (_margins * 2)
height: channelOptColumn.height + ScreenTools.defaultFontPixelHeight
color: qgcPal.windowShade
Column {
id: channelOptColumn
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
anchors.top: parent.top
spacing: ScreenTools.defaultFontPixelHeight
}
QGCLabel { text: ""; visible: _customSimpleMode }
Repeater {
model: _channelOptionCount
Row {
spacing: ScreenTools.defaultFontPixelWidth
property int index: modelData + 7
property Fact nullFact: Fact { }
QGCLabel {
anchors.baseline: optCombo.baseline
text: qsTr("Channel option %1 :").arg(index)
color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text
}
FactComboBox {
id: optCombo
width: ScreenTools.defaultFontPixelWidth * 15
fact: controller.getParameterFact(-1, "CH" + index + "_OPT")
indexModel: false
}
model: 6
QGCLabel { text: _pwmStrings[modelData] }
}
}
RowLayout {
spacing: _margins
visible: controller.simpleModesSupported
QGCLabel { text: qsTr("Simple Mode") }
QGCComboBox {
model: controller.simpleModeNames
currentIndex: controller.simpleMode
onActivated: controller.simpleMode = index
}
}
} // Column - Flight Modes
} // Rectangle - Flight Modes
} // Column - Flight Modes
Column {
spacing: _margins
QGCLabel {
id: channelOptionsLabel
text: qsTr("Switch Options")
font.family: ScreenTools.demiboldFontFamily
}
Rectangle {
id: channelOptionsSettings
width: channelOptColumn.width + (_margins * 2)
height: channelOptColumn.height + ScreenTools.defaultFontPixelHeight
color: qgcPal.windowShade
Column {
id: channelOptColumn
anchors.margins: ScreenTools.defaultFontPixelWidth
anchors.left: parent.left
anchors.top: parent.top
spacing: ScreenTools.defaultFontPixelHeight
Repeater {
model: _rcOptionStop - _rcOptionStart + 1
Row {
spacing: ScreenTools.defaultFontPixelWidth
property int index: modelData + _rcOptionStart
property Fact nullFact: Fact { }
QGCLabel {
anchors.baseline: optCombo.baseline
text: qsTr("Channel option %1 :").arg(index)
color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text
}
FactComboBox {
id: optCombo
width: ScreenTools.defaultFontPixelWidth * 15
fact: controller.getParameterFact(-1, "r.RC" + index + "_OPTION")
indexModel: false
}
} // Repeater -- Channel options
} // Column - Channel options
} // Rectangle - Channel options
} // Column - Channel options
} // Flow
}
} // Repeater -- Channel options
} // Column - Channel options
} // Rectangle - Channel options
} // Column - Channel options
} // Flow
} // Component - flightModePageComponent
} // SetupPage
......@@ -14,13 +14,48 @@
#include <QVariant>
#include <QQmlProperty>
bool APMFlightModesComponentController::_typeRegistered = false;
APMFlightModesComponentController::APMFlightModesComponentController(void)
: _activeFlightMode(0)
, _channelCount(Vehicle::cMaxRcChannels)
: _rover (_vehicle->rover())
, _activeFlightMode (0)
, _channelCount (Vehicle::cMaxRcChannels)
, _simpleMode (SimpleModeStandard)
, _simpleModeFact (_rover ? nullptr : getParameterFact(-1, "SIMPLE"))
, _superSimpleModeFact (_rover ? nullptr : getParameterFact(-1, "SUPER_SIMPLE"))
, _simpleModesSupported (_simpleModeFact && _superSimpleModeFact)
{
if (!_typeRegistered) {
qmlRegisterUncreatableType<APMFlightModesComponentController>("QGroundControl.Controllers", 1, 0, "APMFlightModesComponentController", "Reference only");
}
_modeParamPrefix = _vehicle->rover() ? QStringLiteral("MODE") : QStringLiteral("FLTMODE");
_modeChannelParam = _vehicle->rover() ? QStringLiteral("MODE_CH") : QStringLiteral("FLTMODE_CH");
_simpleModeNames << tr("Off") << tr("Simple") << tr("Super-Simple") << tr("Custom");
for (int i=0; i<_cFltModes; i++) {
_simpleModeEnabled.append(QVariant(false));
_superSimpleModeEnabled.append(QVariant(false));
}
if (!_rover) {
_setupSimpleModeEnabled();
uint8_t simpleModeValue = static_cast<uint8_t>(_simpleModeFact->rawValue().toUInt());
uint8_t superSimpleModeValue = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toUInt());
if (simpleModeValue == 0 && superSimpleModeValue == 0) {
_simpleMode = SimpleModeStandard;
} else if (simpleModeValue == _allSimpleBits && superSimpleModeValue == 0) {
_simpleMode = SimpleModeSimple;
} else if (simpleModeValue == 0 && superSimpleModeValue == _allSimpleBits) {
_simpleMode = SimpleModeSuperSimple;
} else {
_simpleMode = SimpleModeCustom;
}
connect(this, &APMFlightModesComponentController::simpleModeChanged, this, &APMFlightModesComponentController::_updateSimpleParamsFromSimpleMode);
}
QStringList usedParams;
for (int i=1; i<7; i++) {
usedParams << QStringLiteral("%1%2").arg(_modeParamPrefix).arg(i);
......@@ -29,8 +64,10 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
return;
}
_rgChannelOptionEnabled << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false);
for (int i=0; i<_cChannelOptions; i++) {
_rgChannelOptionEnabled.append(QVariant(false));
}
connect(_vehicle, &Vehicle::rcChannelsChanged, this, &APMFlightModesComponentController::_rcChannelsChanged);
}
......@@ -65,7 +102,7 @@ void APMFlightModesComponentController::_rcChannelsChanged(int channelCount, int
}
emit activeFlightModeChanged(_activeFlightMode);
for (int i=0; i<6; i++) {
for (int i=0; i<_cChannelOptions; i++) {
_rgChannelOptionEnabled[i] = QVariant(false);
channelValue = pwmValues[i+6];
if (channelValue > 1800) {
......@@ -74,3 +111,66 @@ void APMFlightModesComponentController::_rcChannelsChanged(int channelCount, int
}
emit channelOptionEnabledChanged();
}
void APMFlightModesComponentController::_updateSimpleParamsFromSimpleMode(void)
{
int newSimpleModeValue = 0;
int newSuperSimpleModeValue = 0;
if (_simpleMode == SimpleModeSimple) {
newSimpleModeValue = _allSimpleBits;
} else if (_simpleMode == SimpleModeSuperSimple) {
newSuperSimpleModeValue = _allSimpleBits;
}
for (int i=0; i<_cFltModes; i++) {
_simpleModeEnabled[i] = false;
_superSimpleModeEnabled[i] = false;
}
emit simpleModeEnabledChanged();
emit superSimpleModeEnabledChanged();
_simpleModeFact->setRawValue(newSimpleModeValue);
_superSimpleModeFact->setRawValue(newSuperSimpleModeValue);
}
void APMFlightModesComponentController::setSimpleMode(int fltModeIndex, bool enabled)
{
if (fltModeIndex < _cFltModes) {
uint8_t mode = static_cast<uint8_t>(_simpleModeFact->rawValue().toInt());
if (enabled) {
mode |= 1 << fltModeIndex;
} else {
mode &= ~(1 << fltModeIndex);
}
_simpleModeFact->setRawValue(mode);
}
}
void APMFlightModesComponentController::setSuperSimpleMode(int fltModeIndex, bool enabled)
{
if (fltModeIndex < _cFltModes) {
uint8_t mode = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toInt());
if (enabled) {
mode |= 1 << fltModeIndex;
} else {
mode &= ~(1 << fltModeIndex);
}
_superSimpleModeFact->setRawValue(mode);
}
}
void APMFlightModesComponentController::_setupSimpleModeEnabled(void)
{
uint8_t simpleMode = static_cast<uint8_t>(_simpleModeFact->rawValue().toUInt());
uint8_t superSimpleMode = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toUInt());
for (int i=0; i<_cFltModes; i++) {
uint8_t bitSet = static_cast<uint8_t>(1 << i);
_simpleModeEnabled[i] = !!(simpleMode & bitSet);
_superSimpleModeEnabled[i] = !!(superSimpleMode & bitSet);
}
emit simpleModeEnabledChanged();
emit superSimpleModeEnabledChanged();
}
......@@ -27,30 +27,66 @@ class APMFlightModesComponentController : public FactPanelController
Q_OBJECT
public:
enum SimpleModeValues {
SimpleModeStandard = 0,
SimpleModeSimple,
SimpleModeSuperSimple,
SimpleModeCustom
};
Q_ENUM(SimpleModeValues)
APMFlightModesComponentController(void);
Q_PROPERTY(QString modeParamPrefix MEMBER _modeParamPrefix CONSTANT)
Q_PROPERTY(QString modeChannelParam MEMBER _modeChannelParam CONSTANT)
Q_PROPERTY(int activeFlightMode READ activeFlightMode NOTIFY activeFlightModeChanged)
Q_PROPERTY(int channelCount MEMBER _channelCount CONSTANT)
Q_PROPERTY(QVariantList channelOptionEnabled READ channelOptionEnabled NOTIFY channelOptionEnabledChanged)
Q_PROPERTY(QString modeParamPrefix MEMBER _modeParamPrefix CONSTANT)
Q_PROPERTY(QString modeChannelParam MEMBER _modeChannelParam CONSTANT)
Q_PROPERTY(int activeFlightMode READ activeFlightMode NOTIFY activeFlightModeChanged)
Q_PROPERTY(int channelCount MEMBER _channelCount CONSTANT)
Q_PROPERTY(QVariantList channelOptionEnabled READ channelOptionEnabled NOTIFY channelOptionEnabledChanged)
Q_PROPERTY(bool simpleModesSupported MEMBER _simpleModesSupported CONSTANT)
Q_PROPERTY(QStringList simpleModeNames MEMBER _simpleModeNames CONSTANT)
Q_PROPERTY(int simpleMode MEMBER _simpleMode NOTIFY simpleModeChanged)
Q_PROPERTY(QVariantList simpleModeEnabled MEMBER _simpleModeEnabled NOTIFY simpleModeEnabledChanged)
Q_PROPERTY(QVariantList superSimpleModeEnabled MEMBER _superSimpleModeEnabled NOTIFY superSimpleModeEnabledChanged)
Q_INVOKABLE void setSimpleMode(int fltModeIndex, bool enabled);
Q_INVOKABLE void setSuperSimpleMode(int fltModeIndex, bool enabled);
int activeFlightMode(void) const { return _activeFlightMode; }
QVariantList channelOptionEnabled(void) const { return _rgChannelOptionEnabled; }
signals:
void activeFlightModeChanged(int activeFlightMode);
void channelOptionEnabledChanged(void);
void activeFlightModeChanged (int activeFlightMode);
void channelOptionEnabledChanged (void);
void simpleModeChanged (int simpleMode);
void simpleModeEnabledChanged (void);
void superSimpleModeEnabledChanged (void);
private slots:
void _rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels]);
void _rcChannelsChanged (int channelCount, int pwmValues[Vehicle::cMaxRcChannels]);
void _updateSimpleParamsFromSimpleMode (void);
void _setupSimpleModeEnabled (void);
private:
bool _rover;
QString _modeParamPrefix;
QString _modeChannelParam;
int _activeFlightMode;
int _channelCount;
QVariantList _rgChannelOptionEnabled;
QStringList _simpleModeNames;
int _simpleMode;
Fact* _simpleModeFact;
Fact* _superSimpleModeFact;
bool _simpleModesSupported;
QVariantList _simpleModeEnabled;
QVariantList _superSimpleModeEnabled;
static const uint8_t _allSimpleBits = 0x3F;
static const int _cChannelOptions = 10;
static const int _cSimpleModeBits = 8;
static const int _cFltModes = 6;
static bool _typeRegistered;
};
#endif
......@@ -516,7 +516,7 @@ SetupPage {
QGCLabel {
width: parent.width
wrapMode: Text.WordWrap
text: qsTr("Measure battery voltage using an external voltmeter and enter the value below. Click Calculate to set the new voltage multiplier.")
text: qsTr("Measure battery voltage using an external voltmeter and enter the value below. Click Calculate to set the new adjusted voltage multiplier.")
}
Grid {
......@@ -537,7 +537,7 @@ SetupPage {
}
QGCButton {
text: "Calculate"
text: qsTr("Calculate And Set")
onClicked: {
var measuredVoltageValue = parseFloat(measuredVoltage.text)
......@@ -599,7 +599,7 @@ SetupPage {
}
QGCButton {
text: "Calculate"
text: qsTr("Calculate And Set")
onClicked: {
var measuredCurrentValue = parseFloat(measuredCurrent.text)
......
......@@ -3409,7 +3409,23 @@ QString Vehicle::firmwareVersionTypeString(void) const
void Vehicle::rebootVehicle()
{
_autoDisconnect = true;
sendMavCommand(_defaultComponentId, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, true, 1.0f);
mavlink_message_t msg;
mavlink_command_long_t cmd;
memset(&cmd, 0, sizeof(cmd));
cmd.target_system = _id;
cmd.target_component = _defaultComponentId;
cmd.command = MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN;
cmd.confirmation = 0;
cmd.param1 = 1;
cmd.param2 = cmd.param3 = cmd.param4 = cmd.param5 = cmd.param6 = cmd.param7 = 0;
mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
&cmd);
sendMessageOnLink(priorityLink(), msg);
}
void Vehicle::setSoloFirmware(bool soloFirmware)
......
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