Commit 93f7147b authored by dogmaphobic's avatar dogmaphobic

Merge remote-tracking branch 'MavLink/master' into messageBox

* MavLink/master:
  Remove QGCMessageBox usage
  Change window close sequence to prompt user from Qml side
  Fix live values
  Clear unsent channels
  Live flight mode config

Conflicts:
	src/ui/MainWindow.h
parents d06bdf8e c990e079
...@@ -77,11 +77,14 @@ QGCView { ...@@ -77,11 +77,14 @@ QGCView {
Row { Row {
spacing: ScreenTools.defaultFontPixelWidth spacing: ScreenTools.defaultFontPixelWidth
property int index: modelData + 1 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 { QGCLabel {
anchors.baseline: modeCombo.baseline anchors.baseline: modeCombo.baseline
text: "Flight Mode " + index + ":" text: "Flight Mode " + index + ":"
color: controller.activeFlightMode == index ? qgcPal.buttonHighlight : qgcPal.text
} }
FactComboBox { FactComboBox {
...@@ -91,56 +94,9 @@ QGCView { ...@@ -91,56 +94,9 @@ QGCView {
indexModel: false indexModel: false
} }
QGCCheckBox { QGCLabel {
id: simple
anchors.baseline: modeCombo.baseline
text: "Simple Mode"
visible: !controller.fixedWing
checked: isChecked()
onClicked: {
var simpleFact = controller.getParameterFact(-1, "SIMPLE")
if (checked) {
simpleFact.value |= 1 << modelData
} else {
simpleFact.value &= ~modelData
}
}
function isChecked() {
if (simple.visible) {
var simpleFact = controller.getParameterFact(-1, "SIMPLE")
return simpleFact.value & (1 << modelData)
} else {
return false;
}
}
}
QGCCheckBox {
id: superSimple
anchors.baseline: modeCombo.baseline anchors.baseline: modeCombo.baseline
text: "Super Simple Mode" text: pwmStrings[modelData]
visible: !controller.fixedWing
checked: isChecked()
onClicked: {
var simpleFact = controller.getParameterFact(-1, "SUPER_SIMPLE")
if (checked) {
simpleFact.value |= 1 << modelData
} else {
simpleFact.value &= ~modelData
}
}
function isChecked() {
if (superSimple.visible) {
var simpleFact = controller.getParameterFact(-1, "SUPER_SIMPLE")
return simpleFact.value & (1 << modelData)
} else {
return false;
}
}
} }
} }
} // Repeater - Flight Modes } // Repeater - Flight Modes
...@@ -176,6 +132,9 @@ QGCView { ...@@ -176,6 +132,9 @@ QGCView {
QGCLabel { QGCLabel {
anchors.baseline: optCombo.baseline anchors.baseline: optCombo.baseline
text: "Channel option " + index + ":" text: "Channel option " + index + ":"
color: controller.channelOptionEnabled[modelData] ? qgcPal.buttonHighlight : qgcPal.text
Component.onCompleted: console.log(index, controller.channelOptionEnabled[modelData])
} }
FactComboBox { FactComboBox {
......
...@@ -29,7 +29,9 @@ ...@@ -29,7 +29,9 @@
#include <QQmlProperty> #include <QQmlProperty>
APMFlightModesComponentController::APMFlightModesComponentController(void) APMFlightModesComponentController::APMFlightModesComponentController(void)
: _channelCount(Vehicle::cMaxRcChannels) : _activeFlightMode(0)
, _channelCount(Vehicle::cMaxRcChannels)
, _fixedWing(_vehicle->vehicleType() == MAV_TYPE_FIXED_WING)
{ {
QStringList usedParams; QStringList usedParams;
usedParams << "FLTMODE1" << "FLTMODE2" << "FLTMODE3" << "FLTMODE4" << "FLTMODE5" << "FLTMODE6"; usedParams << "FLTMODE1" << "FLTMODE2" << "FLTMODE3" << "FLTMODE4" << "FLTMODE5" << "FLTMODE6";
...@@ -37,78 +39,40 @@ APMFlightModesComponentController::APMFlightModesComponentController(void) ...@@ -37,78 +39,40 @@ APMFlightModesComponentController::APMFlightModesComponentController(void)
return; return;
} }
_init(); _rgChannelOptionEnabled << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false);
_validateConfiguration();
connect(_vehicle, &Vehicle::rcChannelsChanged, this, &APMFlightModesComponentController::_rcChannelsChanged); connect(_vehicle, &Vehicle::rcChannelsChanged, this, &APMFlightModesComponentController::_rcChannelsChanged);
} }
void APMFlightModesComponentController::_init(void) /// Connected to Vehicle::rcChannelsChanged signal
void APMFlightModesComponentController::_rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels])
{ {
_fixedWing = _vehicle->vehicleType() == MAV_TYPE_FIXED_WING; Q_UNUSED(channelCount);
}
/// This will look for parameter settings which would cause the config to not run correctly. _activeFlightMode = 0;
/// It will set _validConfiguration and _configurationErrors as needed. int channelValue = pwmValues[4];
void APMFlightModesComponentController::_validateConfiguration(void) if (channelValue != -1) {
{ bool found = false;
_validConfiguration = true; int rgThreshold[] = { 1230, 1360, 1490, 1620, 1749 };
#if 0 for (int i=0; i<5; i++) {
if (channelValue <= rgThreshold[i]) {
// Make sure switches are valid and within channel range _activeFlightMode = i + 1;
found = true;
QStringList switchParams; break;
QList<int> switchMappings;
switchParams << "RC_MAP_MODE_SW" << "RC_MAP_ACRO_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_OFFB_SW";
for(int i=0; i<switchParams.count(); i++) {
int map = getParameterFact(FactSystem::defaultComponentId, switchParams[i])->rawValue().toInt();
switchMappings << map;
if (map < 0 || map > _channelCount) {
_validConfiguration = false;
_configurationErrors += QString("%1 is set to %2. Mapping must between 0 and %3 (inclusive).\n").arg(switchParams[i]).arg(map).arg(_channelCount);
}
}
// Make sure mode switches are not double-mapped
QStringList attitudeParams;
attitudeParams << "RC_MAP_THROTTLE" << "RC_MAP_YAW" << "RC_MAP_PITCH" << "RC_MAP_ROLL" << "RC_MAP_FLAPS" << "RC_MAP_AUX1" << "RC_MAP_AUX2";
for (int i=0; i<attitudeParams.count(); i++) {
int map = getParameterFact(FactSystem::defaultComponentId, attitudeParams[i])->rawValue().toInt();
for (int j=0; j<switchParams.count(); j++) {
if (map != 0 && map == switchMappings[j]) {
_validConfiguration = false;
_configurationErrors += QString("%1 is set to same channel as %2.\n").arg(switchParams[j]).arg(attitudeParams[i]);
} }
} }
} if (!found) {
_activeFlightMode = 6;
// Validate thresholds within range
QStringList thresholdParams;
thresholdParams << "RC_ASSIST_TH" << "RC_AUTO_TH" << "RC_ACRO_TH" << "RC_POSCTL_TH" << "RC_LOITER_TH" << "RC_RETURN_TH" << "RC_OFFB_TH";
foreach(QString thresholdParam, thresholdParams) {
float threshold = getParameterFact(-1, thresholdParam)->rawValue().toFloat();
if (threshold < 0.0f || threshold > 1.0f) {
_validConfiguration = false;
_configurationErrors += QString("%1 is set to %2. Threshold must between 0.0 and 1.0 (inclusive).\n").arg(thresholdParam).arg(threshold);
} }
} }
#endif emit activeFlightModeChanged(_activeFlightMode);
}
/// Connected to Vehicle::rcChannelsChanged signal for (int i=0; i<6; i++) {
void APMFlightModesComponentController::_rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels]) _rgChannelOptionEnabled[i] = QVariant(false);
{ channelValue = pwmValues[i+6];
for (int channel=0; channel<channelCount; channel++) { if (channelValue != -1 && channelValue > 1800) {
_rcValues[channel] = pwmValues[channel]; _rgChannelOptionEnabled[i] = QVariant(true);
}
} }
emit channelOptionEnabledChanged();
} }
...@@ -42,25 +42,26 @@ class APMFlightModesComponentController : public FactPanelController ...@@ -42,25 +42,26 @@ class APMFlightModesComponentController : public FactPanelController
public: public:
APMFlightModesComponentController(void); APMFlightModesComponentController(void);
Q_PROPERTY(int channelCount MEMBER _channelCount CONSTANT) Q_PROPERTY(int activeFlightMode READ activeFlightMode NOTIFY activeFlightModeChanged)
Q_PROPERTY(bool fixedWing MEMBER _fixedWing CONSTANT) Q_PROPERTY(int channelCount MEMBER _channelCount CONSTANT)
Q_PROPERTY(QString reservedChannels MEMBER _reservedChannels CONSTANT) Q_PROPERTY(QVariantList channelOptionEnabled READ channelOptionEnabled NOTIFY channelOptionEnabledChanged)
Q_PROPERTY(bool fixedWing MEMBER _fixedWing CONSTANT)
int activeFlightMode(void) { return _activeFlightMode; }
QVariantList channelOptionEnabled(void) { return _rgChannelOptionEnabled; }
signals:
void activeFlightModeChanged(int activeFlightMode);
void channelOptionEnabledChanged(void);
private slots: private slots:
void _rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels]); void _rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels]);
private: private:
void _init(void); int _activeFlightMode;
void _validateConfiguration(void); int _channelCount;
QVariantList _rgChannelOptionEnabled;
bool _fixedWing; bool _fixedWing;
int _rcValues[Vehicle::cMaxRcChannels];
bool _validConfiguration;
QString _configurationErrors;
int _channelCount;
QString _reservedChannels;
}; };
#endif #endif
...@@ -26,8 +26,8 @@ ...@@ -26,8 +26,8 @@
/// @author Don Gagne <don@thegagnes.com /// @author Don Gagne <don@thegagnes.com
#include "RadioComponentController.h" #include "RadioComponentController.h"
#include "QGCMessageBox.h"
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
#include "QGCApplication.h"
#include <QSettings> #include <QSettings>
......
...@@ -657,7 +657,6 @@ void ParameterLoader::_saveToEEPROM(void) ...@@ -657,7 +657,6 @@ void ParameterLoader::_saveToEEPROM(void)
QString ParameterLoader::readParametersFromStream(QTextStream& stream) QString ParameterLoader::readParametersFromStream(QTextStream& stream)
{ {
QString errors; QString errors;
bool userWarned = false;
while (!stream.atEnd()) { while (!stream.atEnd()) {
QString line = stream.readLine(); QString line = stream.readLine();
...@@ -665,16 +664,8 @@ QString ParameterLoader::readParametersFromStream(QTextStream& stream) ...@@ -665,16 +664,8 @@ QString ParameterLoader::readParametersFromStream(QTextStream& stream)
QStringList wpParams = line.split("\t"); QStringList wpParams = line.split("\t");
int lineMavId = wpParams.at(0).toInt(); int lineMavId = wpParams.at(0).toInt();
if (wpParams.size() == 5) { if (wpParams.size() == 5) {
if (!userWarned && (_vehicle->id() != lineMavId)) { if (_vehicle->id() != lineMavId) {
userWarned = true; return QString("The parameters in the stream have been saved from System Id %1, but the current vehicle has the System Id %2.").arg(lineMavId).arg(_vehicle->id());
QString msg("The parameters in the stream have been saved from System Id %1, but the current vehicle has the System Id %2.");
QGCMessageBox::StandardButton button = QGCMessageBox::warning("Parameter Load",
msg.arg(lineMavId).arg(_vehicle->id()),
QGCMessageBox::Ok | QGCMessageBox::Cancel,
QGCMessageBox::Cancel);
if (button == QGCMessageBox::Cancel) {
return QString();
}
} }
int componentId = wpParams.at(1).toInt(); int componentId = wpParams.at(1).toInt();
......
...@@ -455,9 +455,7 @@ bool QGCApplication::_initForNormalAppBoot(void) ...@@ -455,9 +455,7 @@ bool QGCApplication::_initForNormalAppBoot(void)
/// settings. /// settings.
QString savedFilesLocation = settings.value(_savedFilesLocationKey).toString(); QString savedFilesLocation = settings.value(_savedFilesLocationKey).toString();
if (savedFilesLocation.isEmpty()) { if (savedFilesLocation.isEmpty()) {
QGCMessageBox::warning( showMessage("The location to save files to is invalid, or cannot be written to. Please provide a new one.");
tr("Bad save location"),
tr("The location to save files to is invalid, or cannot be written to. Please provide a new one."));
mainWindow->showSettings(); mainWindow->showSettings();
} }
...@@ -705,10 +703,7 @@ void QGCApplication::_missingParamsDisplay(void) ...@@ -705,10 +703,7 @@ void QGCApplication::_missingParamsDisplay(void)
} }
_missingParams.clear(); _missingParams.clear();
QGCMessageBox::critical( showMessage(QString("Parameters missing from firmware: %1.\n\nYou should quit QGroundControl immediately and update your firmware.").arg(params));
"Missing Parameters",
QString("Parameters missing from firmware: %1.\n\n"
"You should quit QGroundControl immediately and update your firmware.").arg(params));
} }
void QGCApplication::showMessage(const QString& message) void QGCApplication::showMessage(const QString& message)
...@@ -717,6 +712,6 @@ void QGCApplication::showMessage(const QString& message) ...@@ -717,6 +712,6 @@ void QGCApplication::showMessage(const QString& message)
if (mainWindow) { if (mainWindow) {
mainWindow->showMessage(message); mainWindow->showMessage(message);
} else { } else {
QGCMessageBox::information("", message); qWarning() << "showMessage with no mainWindow" << message;
} }
} }
...@@ -60,7 +60,7 @@ bool QGCQuickWidget::setSource(const QUrl& qmlUrl) ...@@ -60,7 +60,7 @@ bool QGCQuickWidget::setSource(const QUrl& qmlUrl)
errorList += error.toString(); errorList += error.toString();
errorList += "\n"; errorList += "\n";
} }
QGCMessageBox::warning(tr("Qml Error"), tr("Source not ready: Status(%1)\nErrors:\n%2").arg(status()).arg(errorList)); qgcApp()->showMessage(QString("Source not ready: Status(%1)\nErrors:\n%2").arg(status()).arg(errorList));
return false; return false;
} }
......
...@@ -353,6 +353,10 @@ void Vehicle::_handleRCChannelsRaw(mavlink_message_t& message) ...@@ -353,6 +353,10 @@ void Vehicle::_handleRCChannelsRaw(mavlink_message_t& message)
int pwmValues[cMaxRcChannels]; int pwmValues[cMaxRcChannels];
int channelCount = 0; int channelCount = 0;
for (int i=0; i<cMaxRcChannels; i++) {
pwmValues[i] = -1;
}
for (int i=0; i<8; i++) { for (int i=0; i<8; i++) {
uint16_t channelValue = *_rgChannelvalues[i]; uint16_t channelValue = *_rgChannelvalues[i];
......
...@@ -425,24 +425,20 @@ void MainWindow::showStatusBarCallback(bool checked) ...@@ -425,24 +425,20 @@ void MainWindow::showStatusBarCallback(bool checked)
checked ? statusBar()->show() : statusBar()->hide(); checked ? statusBar()->show() : statusBar()->hide();
} }
void MainWindow::acceptWindowClose(void)
{
qgcApp()->toolbox()->linkManager()->shutdown();
// The above shutdown causes a flurry of activity as the vehicle components are removed. This in turn
// causes the Windows Version of Qt to crash if you allow the close event to be accepted. In order to prevent
// the crash, we ignore the close event and setup a delayed timer to close the window after things settle down.
QTimer::singleShot(1500, this, &MainWindow::_closeWindow);
}
void MainWindow::closeEvent(QCloseEvent *event) void MainWindow::closeEvent(QCloseEvent *event)
{ {
// Disallow window close if there are active connections // Disallow window close if there are active connections
if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count()) { if (qgcApp()->toolbox()->multiVehicleManager()->vehicles()->count()) {
QGCMessageBox::StandardButton button = emit showWindowCloseMessage();
QGCMessageBox::warning(
tr("QGroundControl close"),
tr("There are still active connections to vehicles. Do you want to disconnect these before closing?"),
QMessageBox::Yes | QMessageBox::Cancel,
QMessageBox::Cancel);
if (button == QMessageBox::Yes) {
qgcApp()->toolbox()->linkManager()->shutdown();
// The above disconnect causes a flurry of activity as the vehicle components are removed. This in turn
// causes the Windows Version of Qt to crash if you allow the close event to be accepted. In order to prevent
// the crash, we ignore the close event and setup a delayed timer to close the window after things settle down.
QTimer::singleShot(1500, this, &MainWindow::_closeWindow);
}
event->ignore(); event->ignore();
return; return;
} }
......
...@@ -94,6 +94,9 @@ public: ...@@ -94,6 +94,9 @@ public:
/// @brief Show message in lower message window /// @brief Show message in lower message window
void showMessage(const QString message); void showMessage(const QString message);
// Called from MainWindow.qml when the user accepts the window close dialog
Q_INVOKABLE void acceptWindowClose(void);
public slots: public slots:
/** @brief Show the application settings */ /** @brief Show the application settings */
void showSettings(); void showSettings();
...@@ -135,6 +138,7 @@ protected slots: ...@@ -135,6 +138,7 @@ protected slots:
* this incoherent. * this incoherent.
*/ */
void handleActiveViewActionState(bool triggered); void handleActiveViewActionState(bool triggered);
signals: signals:
// Signals the Qml to show the specified view // Signals the Qml to show the specified view
void showFlyView(void); void showFlyView(void);
...@@ -142,6 +146,7 @@ signals: ...@@ -142,6 +146,7 @@ signals:
void showSetupView(void); void showSetupView(void);
void showCriticalMessage(const QString& message); void showCriticalMessage(const QString& message);
void showWindowCloseMessage(void);
// These are used for unit testing // These are used for unit testing
void showSetupFirmware(void); void showSetupFirmware(void);
......
...@@ -23,6 +23,7 @@ along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>. ...@@ -23,6 +23,7 @@ along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
import QtQuick 2.5 import QtQuick 2.5
import QtQuick.Controls 1.2 import QtQuick.Controls 1.2
import QtQuick.Dialogs 1.2
import QtPositioning 5.2 import QtPositioning 5.2
import QGroundControl 1.0 import QGroundControl 1.0
...@@ -95,6 +96,8 @@ Item { ...@@ -95,6 +96,8 @@ Item {
onShowCriticalMessage: showCriticalMessage(message) onShowCriticalMessage: showCriticalMessage(message)
onShowWindowCloseMessage: windowCloseDialog.open()
// The following are use for unit testing only // The following are use for unit testing only
onShowSetupFirmware: setupViewLoader.item.showFirmwarePanel() onShowSetupFirmware: setupViewLoader.item.showFirmwarePanel()
...@@ -185,13 +188,24 @@ Item { ...@@ -185,13 +188,24 @@ Item {
function showPopUp(dropItem, centerX) { function showPopUp(dropItem, centerX) {
if(currentPopUp) { if(currentPopUp) {
currentPopUp.close() currentPopUp.close()
} }
indicatorDropdown.centerX = centerX indicatorDropdown.centerX = centerX
indicatorDropdown.sourceComponent = dropItem indicatorDropdown.sourceComponent = dropItem
indicatorDropdown.visible = true indicatorDropdown.visible = true
currentPopUp = indicatorDropdown currentPopUp = indicatorDropdown
} }
MessageDialog {
id: windowCloseDialog
title: "QGroundControl close"
text: "There are still active connections to vehicles. Do you want to disconnect these before closing?"
standardButtons: StandardButton.Yes | StandardButton.Cancel
modality: Qt.ApplicationModal
visible: false
onYes: controller.acceptWindowClose()
}
//-- Left Settings Menu //-- Left Settings Menu
Loader { Loader {
id: leftPanel id: leftPanel
......
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