From adbbdb45d3fd55dc662cf7677c763852cc38c790 Mon Sep 17 00:00:00 2001 From: Bryant Date: Thu, 20 Jun 2013 17:00:10 -0700 Subject: [PATCH] All UI elements in the JoystickWidget window are now updated properly when switching UASes, which was the last major issue with this code. A single small bug remains involving the UI not updating the axis values when switching joysticks until the axis is moved. --- src/input/JoystickInput.cc | 39 +++++++++++--------------------------- src/input/JoystickInput.h | 7 ++++++- src/ui/JoystickAxis.cc | 21 ++++++++++---------- src/ui/JoystickAxis.h | 6 ++++++ src/ui/JoystickButton.cc | 10 ++++++---- src/ui/JoystickButton.h | 3 ++- src/ui/JoystickButton.ui | 4 ++-- src/ui/JoystickWidget.cc | 16 ++++++++-------- 8 files changed, 51 insertions(+), 55 deletions(-) diff --git a/src/input/JoystickInput.cc b/src/input/JoystickInput.cc index f1b7dc261d..4903ae8146 100644 --- a/src/input/JoystickInput.cc +++ b/src/input/JoystickInput.cc @@ -71,9 +71,7 @@ void JoystickInput::loadGeneralSettings() // Deal with settings specific to the JoystickInput settings.beginGroup("JOYSTICK_INPUT"); isEnabled = settings.value("ENABLED", false).toBool(); - qDebug() << "JoystickInput: Loading enabled setting (" << isEnabled << ")"; joystickName = settings.value("JOYSTICK_NAME", "").toString(); - qDebug() << "JoystickInput: Loading last joystick setting (" << joystickName << ")"; settings.endGroup(); } @@ -106,7 +104,6 @@ void JoystickInput::loadJoystickSettings() { settings.setArrayIndex(j); int systemType = settings.value("SYSTEM_TYPE", 0).toInt(); - qDebug() << "Loading joystick settings for (" << autopilotType << "," << systemType << ")"; // Now that both the autopilot and system type are available, update some references. QMap* joystickAxesInverted = &joystickSettings[autopilotType][systemType].axesInverted; @@ -121,7 +118,6 @@ void JoystickInput::loadJoystickSettings() int index = settings.value("INDEX", 0).toInt(); bool inverted = settings.value("INVERTED", false).toBool(); joystickAxesInverted->insert(index, inverted); - qDebug() << "Loading inversion status (" << inverted << ") for axis " << index; } settings.endArray(); @@ -133,7 +129,6 @@ void JoystickInput::loadJoystickSettings() int index = settings.value("INDEX", 0).toInt(); bool limited = settings.value("LIMITED", false).toBool(); joystickAxesLimited->insert(index, limited); - qDebug() << "Loading limited status (" << limited << ") for axis " << index; } settings.endArray(); @@ -145,7 +140,6 @@ void JoystickInput::loadJoystickSettings() int index = settings.value("INDEX", 0).toInt(); int action = settings.value("ACTION", 0).toInt(); joystickButtonActions->insert(index, action); - qDebug() << "Loading action (" << action << ") for button " << index; } settings.endArray(); } @@ -198,7 +192,6 @@ void JoystickInput::storeJoystickSettings() const int systemType = j.key(); settings.setValue("SYSTEM_TYPE", systemType); - qDebug() << "Saving joystick settings for (" << autopilotType << "," << systemType << ")"; // Now that both the autopilot and system type are available, update some references. QMapIterator joystickAxesInverted(joystickSettings[autopilotType][systemType].axesInverted); @@ -218,7 +211,6 @@ void JoystickInput::storeJoystickSettings() const int index = joystickAxesInverted.key(); settings.setValue("INDEX", index); settings.setValue("INVERTED", inverted); - qDebug() << "Saving inversion status (" << inverted << ") for axis " << index; } } settings.endArray(); @@ -235,7 +227,6 @@ void JoystickInput::storeJoystickSettings() const int index = joystickAxesLimited.key(); settings.setValue("INDEX", index); settings.setValue("LIMITED", limited); - qDebug() << "Saving limited status (" << limited << ") for axis " << index; } } settings.endArray(); @@ -252,7 +243,6 @@ void JoystickInput::storeJoystickSettings() const int index = joystickButtonActions.key(); settings.setValue("INDEX", index); settings.setValue("ACTION", action); - qDebug() << "Saving action (" << action << ") for button " << index; } } settings.endArray(); @@ -302,9 +292,12 @@ void JoystickInput::setActiveUAS(UASInterface* uas) // Update the joystick settings for a new UAS. autopilotType = uas->getAutopilotType(); systemType = uas->getSystemType(); - qDebug() << "Switching to UAS with autopilot: " << autopilotType << " and system: " << systemType; } + // Make sure any UI elements know we've updated the UAS. The UASManager signal is re-emitted here so that UI elements know to + // update their UAS-specific UI. + emit activeUASSet(uas); + // Load any joystick-specific settings now that the UAS has changed. if (joystickID > -1) { @@ -353,7 +346,7 @@ void JoystickInput::init() for(int i=0; i < numJoysticks; i++ ) { QString name = SDL_JoystickName(i); - qDebug() << QString("\t- %1").arg(name); + qDebug() << QString("\t%1").arg(name); // If we've matched this joystick to what was last opened, note it. // Note: The way this is implemented the LAST joystick of a given name will be opened. @@ -363,8 +356,8 @@ void JoystickInput::init() } SDL_Joystick* x = SDL_JoystickOpen(i); - qDebug() << QString("Number of Axes: %1").arg(QString::number(SDL_JoystickNumAxes(x))); - qDebug() << QString("Number of Buttons: %1").arg(QString::number(SDL_JoystickNumButtons(x))); + qDebug() << QString("\tNumber of Axes: %1").arg(QString::number(SDL_JoystickNumAxes(x))); + qDebug() << QString("\tNumber of Buttons: %1").arg(QString::number(SDL_JoystickNumButtons(x))); SDL_JoystickClose(x); } @@ -410,7 +403,7 @@ void JoystickInput::run() // This is generally not used for controlling a vehicle, but a UI representation, so it being slightly off is fine. // Here we map the joystick axis value into the initial range of [0:1]. float axisValue = SDL_JoystickGetAxis(joystick, i); - if (joystickSettings[autopilotType][systemType].axesLimited[i]) + if (joystickSettings[autopilotType][systemType].axesInverted[i]) { axisValue = (axisValue - calibrationNegative[i]) / (calibrationPositive[i] - calibrationNegative[i]); } @@ -520,36 +513,26 @@ void JoystickInput::setActiveJoystick(int id) // Restore saved settings for this joystick. loadJoystickSettings(); - qDebug() << "Roll: " << rollAxis << ", Pitch: " << pitchAxis << ", Yaw: " << yawAxis << ", Throttle: " << throttleAxis; // Update cached joystick axes values. // Also emit any signals for currently-triggering events joystickAxes.clear(); for (int i = 0; i < joystickNumAxes; i++) { - int axisValue = SDL_JoystickGetAxis(joystick, i); - joystickAxes.append(axisValue); - emit axisValueChanged(i, axisValue); + joystickAxes.append(NAN); } // Update cached joystick button values. // Emit signals for any button events. joystickButtons = 0; - for (int i = 0; i < joystickNumButtons; i++) - { - if (SDL_JoystickGetButton(joystick, i)) - { - emit buttonPressed(i); - joystickButtons |= 1 << i; - } - } - qDebug() << QString("Switching to joystick '%1' with %2 buttons/%3 axes").arg(joystickName, QString::number(joystickNumButtons), QString::number(joystickNumAxes)); } else { joystickNumButtons = 0; joystickNumAxes = 0; } + + emit joystickSettingsChanged(); } void JoystickInput::setAxisMapping(int axis, JOYSTICK_INPUT_MAPPING newMapping) diff --git a/src/input/JoystickInput.h b/src/input/JoystickInput.h index 2d9688c725..97c4263e2a 100644 --- a/src/input/JoystickInput.h +++ b/src/input/JoystickInput.h @@ -49,7 +49,7 @@ struct JoystickSettings { QMap axesLimited; ///< Whether each axis should be limited to only the positive range. Currently this only applies to the throttle axis, but is kept generic here to possibly support other axes. QMap buttonActions; ///< The index of the action associated with every button. }; -Q_DECLARE_METATYPE(JoystickSettings); +Q_DECLARE_METATYPE(JoystickSettings) /** * @brief Joystick input @@ -257,6 +257,11 @@ signals: */ void hatDirectionChanged(int x, int y); + /** @brief Signal that the UAS has been updated for this JoystickInput + * Note that any UI updates should NOT query this object for joystick details. That should be done in response to the joystickSettingsChanged signal. + */ + void activeUASSet(UASInterface*); + /** @brief Signals that new joystick-specific settings were changed. Useful for triggering updates that at dependent on the current joystick. */ void joystickSettingsChanged(); diff --git a/src/ui/JoystickAxis.cc b/src/ui/JoystickAxis.cc index c373d5ba57..5effd6971b 100644 --- a/src/ui/JoystickAxis.cc +++ b/src/ui/JoystickAxis.cc @@ -53,16 +53,9 @@ void JoystickAxis::setRangeLimit(bool newValue) void JoystickAxis::mappingComboBoxChanged(int newMapping) { - if (newMapping == JoystickInput::JOYSTICK_INPUT_MAPPING_THROTTLE) - { - ui->rangeCheckBox->show(); - } - else - { - ui->rangeCheckBox->hide(); - } - emit mappingChanged(id, (JoystickInput::JOYSTICK_INPUT_MAPPING)newMapping); - this->setActiveUAS(UASManager::instance()->getActiveUAS()); + JoystickInput::JOYSTICK_INPUT_MAPPING mapping = (JoystickInput::JOYSTICK_INPUT_MAPPING)newMapping; + emit mappingChanged(id, mapping); + updateUIBasedOnUAS(UASManager::instance()->getActiveUAS(), mapping); } void JoystickAxis::inversionCheckBoxChanged(bool inverted) @@ -76,11 +69,17 @@ void JoystickAxis::rangeCheckBoxChanged(bool limited) } void JoystickAxis::setActiveUAS(UASInterface* uas) +{ + updateUIBasedOnUAS(uas, (JoystickInput::JOYSTICK_INPUT_MAPPING)ui->comboBox->currentIndex()); +} + +void JoystickAxis::updateUIBasedOnUAS(UASInterface* uas, JoystickInput::JOYSTICK_INPUT_MAPPING axisMapping) { // Set the throttle display to only positive if: // * This is the throttle axis AND // * The current UAS can't reverse OR there is no current UAS - if (((uas && !uas->systemCanReverse()) || !uas) && ui->comboBox->currentIndex() == JoystickInput::JOYSTICK_INPUT_MAPPING_THROTTLE) + // This causes us to default to systems with no negative throttle. + if (((uas && !uas->systemCanReverse()) || !uas) && axisMapping == JoystickInput::JOYSTICK_INPUT_MAPPING_THROTTLE) { ui->progressBar->setRange(0, 100); ui->rangeCheckBox->show(); diff --git a/src/ui/JoystickAxis.h b/src/ui/JoystickAxis.h index 9a2124d21d..3fddd57d58 100644 --- a/src/ui/JoystickAxis.h +++ b/src/ui/JoystickAxis.h @@ -38,6 +38,12 @@ public slots: private: int id; ///< The ID for this axis. Corresponds to the IDs used by JoystickInput. Ui::JoystickAxis *ui; + /** + * @brief Update the UI based on both the current UAS and the current axis mapping. + * @param uas The currently-active UAS. + * @param axisMapping The new mapping for this axis. + */ + void updateUIBasedOnUAS(UASInterface* uas, JoystickInput::JOYSTICK_INPUT_MAPPING axisMapping); private slots: /** @brief Handle changes to the mapping dropdown bar. */ diff --git a/src/ui/JoystickButton.cc b/src/ui/JoystickButton.cc index 053d11b10e..97941557ba 100644 --- a/src/ui/JoystickButton.cc +++ b/src/ui/JoystickButton.cc @@ -21,7 +21,7 @@ JoystickButton::~JoystickButton() void JoystickButton::setActiveUAS(UASInterface* uas) { // Disable signals so that changes to joystickAction don't trigger JoystickInput updates. - blockSignals(true); + disconnect(m_ui->joystickAction, SIGNAL(currentIndexChanged(int)), this, SLOT(actionComboBoxChanged(int))); if (uas) { m_ui->joystickAction->setEnabled(true); @@ -32,21 +32,23 @@ void JoystickButton::setActiveUAS(UASInterface* uas) { m_ui->joystickAction->addItem(a->text()); } + m_ui->joystickAction->setCurrentIndex(0); } else { m_ui->joystickAction->setEnabled(false); m_ui->joystickAction->clear(); m_ui->joystickAction->addItem("--"); + m_ui->joystickAction->setCurrentIndex(0); } - blockSignals(false); + connect(m_ui->joystickAction, SIGNAL(currentIndexChanged(int)), this, SLOT(actionComboBoxChanged(int))); } void JoystickButton::setAction(int index) { // Disable signals so that changes to joystickAction don't trigger JoystickInput updates. - //blockSignals(true); + disconnect(m_ui->joystickAction, SIGNAL(currentIndexChanged(int)), this, SLOT(actionComboBoxChanged(int))); // Add one because the default no-action takes the 0-spot. m_ui->joystickAction->setCurrentIndex(index + 1); - //blockSignals(false); + connect(m_ui->joystickAction, SIGNAL(currentIndexChanged(int)), this, SLOT(actionComboBoxChanged(int))); } void JoystickButton::actionComboBoxChanged(int index) diff --git a/src/ui/JoystickButton.h b/src/ui/JoystickButton.h index 92fed4e285..6af5fe3a22 100644 --- a/src/ui/JoystickButton.h +++ b/src/ui/JoystickButton.h @@ -21,7 +21,8 @@ public: public slots: /** @brief Specify the UAS that this axis should track for displaying throttle properly. */ void setActiveUAS(UASInterface* uas); - /** @brieft Specify which action this button should correspond to. */ + /** @brieft Specify which action this button should correspond to. + * Values 0 and higher indicate a specific action, while -1 indicates no action. */ void setAction(int index); signals: diff --git a/src/ui/JoystickButton.ui b/src/ui/JoystickButton.ui index 6dd7805ca6..1598d22273 100644 --- a/src/ui/JoystickButton.ui +++ b/src/ui/JoystickButton.ui @@ -44,7 +44,7 @@ - + 0 0 @@ -69,7 +69,7 @@ false - + 0 0 diff --git a/src/ui/JoystickWidget.cc b/src/ui/JoystickWidget.cc index 2ae22c08c5..d68f644bc6 100644 --- a/src/ui/JoystickWidget.cc +++ b/src/ui/JoystickWidget.cc @@ -3,7 +3,7 @@ #include "ui_JoystickWidget.h" #include "JoystickButton.h" #include "JoystickAxis.h" -#include + #include JoystickWidget::JoystickWidget(JoystickInput* joystick, QWidget *parent) : @@ -30,9 +30,8 @@ JoystickWidget::JoystickWidget(JoystickInput* joystick, QWidget *parent) : // Also watch for when new settings were loaded for the current joystick to do a mass UI refresh. connect(this->joystick, SIGNAL(joystickSettingsChanged()), this, SLOT(updateUI())); - // If the selected joystick is changed, update the joystick and the UI. + // If the selected joystick is changed, update the joystick. connect(m_ui->joystickNameComboBox, SIGNAL(currentIndexChanged(int)), this->joystick, SLOT(setActiveJoystick(int))); - connect(m_ui->joystickNameComboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(createUIForJoystick())); // Initialize the UI to the current JoystickInput state. Also make sure to listen for future changes // so that the UI can be updated. @@ -109,13 +108,15 @@ void JoystickWidget::changeEvent(QEvent *e) void JoystickWidget::updateUI() { + // Update the actions for all of the buttons for (int i = 0; i < buttons.size(); i++) { JoystickButton* button = buttons[i]; int action = joystick->getActionForButton(i); - button->setAction(action + 1); - qDebug() << "JoystickWidget: Updating button " << i << " to action " << action + 1; + button->setAction(action); } + + // Update the axis mappings int rollAxis = joystick->getMappingRollAxis(); int pitchAxis = joystick->getMappingPitchAxis(); int yawAxis = joystick->getMappingYawAxis(); @@ -147,7 +148,6 @@ void JoystickWidget::updateUI() axis->setInverted(inverted); bool limited = joystick->getRangeLimitForAxis(i); axis->setRangeLimit(limited); - qDebug() << "JoystickWidget: Updating axis " << i << " to value:" << value << ", mapping:" << mapping << ", inverted:" << inverted << ", limited:" << limited; } } @@ -175,7 +175,7 @@ void JoystickWidget::createUIForJoystick() JoystickButton* button = new JoystickButton(i, m_ui->buttonBox); button->setAction(joystick->getActionForButton(i)); connect(button, SIGNAL(actionChanged(int,int)), this->joystick, SLOT(setButtonAction(int,int))); - connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), button, SLOT(setActiveUAS(UASInterface*))); + connect(this->joystick, SIGNAL(activeUASSet(UASInterface*)), button, SLOT(setActiveUAS(UASInterface*))); m_ui->buttonLayout->addWidget(button); buttons.append(button); } @@ -218,7 +218,7 @@ void JoystickWidget::createUIForJoystick() connect(axis, SIGNAL(mappingChanged(int,JoystickInput::JOYSTICK_INPUT_MAPPING)), this->joystick, SLOT(setAxisMapping(int,JoystickInput::JOYSTICK_INPUT_MAPPING))); connect(axis, SIGNAL(inversionChanged(int,bool)), this->joystick, SLOT(setAxisInversion(int,bool))); connect(axis, SIGNAL(rangeChanged(int,bool)), this->joystick, SLOT(setAxisRangeLimit(int,bool))); - connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), axis, SLOT(setActiveUAS(UASInterface*))); + connect(this->joystick, SIGNAL(activeUASSet(UASInterface*)), axis, SLOT(setActiveUAS(UASInterface*))); m_ui->axesLayout->addWidget(axis); axes.append(axis); } -- GitLab