Commit adbbdb45 authored by Bryant's avatar Bryant

All UI elements in the JoystickWidget window are now updated properly when...

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.
parent 8268ca2c
...@@ -71,9 +71,7 @@ void JoystickInput::loadGeneralSettings() ...@@ -71,9 +71,7 @@ void JoystickInput::loadGeneralSettings()
// Deal with settings specific to the JoystickInput // Deal with settings specific to the JoystickInput
settings.beginGroup("JOYSTICK_INPUT"); settings.beginGroup("JOYSTICK_INPUT");
isEnabled = settings.value("ENABLED", false).toBool(); isEnabled = settings.value("ENABLED", false).toBool();
qDebug() << "JoystickInput: Loading enabled setting (" << isEnabled << ")";
joystickName = settings.value("JOYSTICK_NAME", "").toString(); joystickName = settings.value("JOYSTICK_NAME", "").toString();
qDebug() << "JoystickInput: Loading last joystick setting (" << joystickName << ")";
settings.endGroup(); settings.endGroup();
} }
...@@ -106,7 +104,6 @@ void JoystickInput::loadJoystickSettings() ...@@ -106,7 +104,6 @@ void JoystickInput::loadJoystickSettings()
{ {
settings.setArrayIndex(j); settings.setArrayIndex(j);
int systemType = settings.value("SYSTEM_TYPE", 0).toInt(); 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. // Now that both the autopilot and system type are available, update some references.
QMap<int, bool>* joystickAxesInverted = &joystickSettings[autopilotType][systemType].axesInverted; QMap<int, bool>* joystickAxesInverted = &joystickSettings[autopilotType][systemType].axesInverted;
...@@ -121,7 +118,6 @@ void JoystickInput::loadJoystickSettings() ...@@ -121,7 +118,6 @@ void JoystickInput::loadJoystickSettings()
int index = settings.value("INDEX", 0).toInt(); int index = settings.value("INDEX", 0).toInt();
bool inverted = settings.value("INVERTED", false).toBool(); bool inverted = settings.value("INVERTED", false).toBool();
joystickAxesInverted->insert(index, inverted); joystickAxesInverted->insert(index, inverted);
qDebug() << "Loading inversion status (" << inverted << ") for axis " << index;
} }
settings.endArray(); settings.endArray();
...@@ -133,7 +129,6 @@ void JoystickInput::loadJoystickSettings() ...@@ -133,7 +129,6 @@ void JoystickInput::loadJoystickSettings()
int index = settings.value("INDEX", 0).toInt(); int index = settings.value("INDEX", 0).toInt();
bool limited = settings.value("LIMITED", false).toBool(); bool limited = settings.value("LIMITED", false).toBool();
joystickAxesLimited->insert(index, limited); joystickAxesLimited->insert(index, limited);
qDebug() << "Loading limited status (" << limited << ") for axis " << index;
} }
settings.endArray(); settings.endArray();
...@@ -145,7 +140,6 @@ void JoystickInput::loadJoystickSettings() ...@@ -145,7 +140,6 @@ void JoystickInput::loadJoystickSettings()
int index = settings.value("INDEX", 0).toInt(); int index = settings.value("INDEX", 0).toInt();
int action = settings.value("ACTION", 0).toInt(); int action = settings.value("ACTION", 0).toInt();
joystickButtonActions->insert(index, action); joystickButtonActions->insert(index, action);
qDebug() << "Loading action (" << action << ") for button " << index;
} }
settings.endArray(); settings.endArray();
} }
...@@ -198,7 +192,6 @@ void JoystickInput::storeJoystickSettings() const ...@@ -198,7 +192,6 @@ void JoystickInput::storeJoystickSettings() const
int systemType = j.key(); int systemType = j.key();
settings.setValue("SYSTEM_TYPE", systemType); 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. // Now that both the autopilot and system type are available, update some references.
QMapIterator<int, bool> joystickAxesInverted(joystickSettings[autopilotType][systemType].axesInverted); QMapIterator<int, bool> joystickAxesInverted(joystickSettings[autopilotType][systemType].axesInverted);
...@@ -218,7 +211,6 @@ void JoystickInput::storeJoystickSettings() const ...@@ -218,7 +211,6 @@ void JoystickInput::storeJoystickSettings() const
int index = joystickAxesInverted.key(); int index = joystickAxesInverted.key();
settings.setValue("INDEX", index); settings.setValue("INDEX", index);
settings.setValue("INVERTED", inverted); settings.setValue("INVERTED", inverted);
qDebug() << "Saving inversion status (" << inverted << ") for axis " << index;
} }
} }
settings.endArray(); settings.endArray();
...@@ -235,7 +227,6 @@ void JoystickInput::storeJoystickSettings() const ...@@ -235,7 +227,6 @@ void JoystickInput::storeJoystickSettings() const
int index = joystickAxesLimited.key(); int index = joystickAxesLimited.key();
settings.setValue("INDEX", index); settings.setValue("INDEX", index);
settings.setValue("LIMITED", limited); settings.setValue("LIMITED", limited);
qDebug() << "Saving limited status (" << limited << ") for axis " << index;
} }
} }
settings.endArray(); settings.endArray();
...@@ -252,7 +243,6 @@ void JoystickInput::storeJoystickSettings() const ...@@ -252,7 +243,6 @@ void JoystickInput::storeJoystickSettings() const
int index = joystickButtonActions.key(); int index = joystickButtonActions.key();
settings.setValue("INDEX", index); settings.setValue("INDEX", index);
settings.setValue("ACTION", action); settings.setValue("ACTION", action);
qDebug() << "Saving action (" << action << ") for button " << index;
} }
} }
settings.endArray(); settings.endArray();
...@@ -302,9 +292,12 @@ void JoystickInput::setActiveUAS(UASInterface* uas) ...@@ -302,9 +292,12 @@ void JoystickInput::setActiveUAS(UASInterface* uas)
// Update the joystick settings for a new UAS. // Update the joystick settings for a new UAS.
autopilotType = uas->getAutopilotType(); autopilotType = uas->getAutopilotType();
systemType = uas->getSystemType(); 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. // Load any joystick-specific settings now that the UAS has changed.
if (joystickID > -1) if (joystickID > -1)
{ {
...@@ -353,7 +346,7 @@ void JoystickInput::init() ...@@ -353,7 +346,7 @@ void JoystickInput::init()
for(int i=0; i < numJoysticks; i++ ) for(int i=0; i < numJoysticks; i++ )
{ {
QString name = SDL_JoystickName(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. // 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. // Note: The way this is implemented the LAST joystick of a given name will be opened.
...@@ -363,8 +356,8 @@ void JoystickInput::init() ...@@ -363,8 +356,8 @@ void JoystickInput::init()
} }
SDL_Joystick* x = SDL_JoystickOpen(i); SDL_Joystick* x = SDL_JoystickOpen(i);
qDebug() << QString("Number of Axes: %1").arg(QString::number(SDL_JoystickNumAxes(x))); qDebug() << QString("\tNumber 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 Buttons: %1").arg(QString::number(SDL_JoystickNumButtons(x)));
SDL_JoystickClose(x); SDL_JoystickClose(x);
} }
...@@ -410,7 +403,7 @@ void JoystickInput::run() ...@@ -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. // 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]. // Here we map the joystick axis value into the initial range of [0:1].
float axisValue = SDL_JoystickGetAxis(joystick, i); 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]); axisValue = (axisValue - calibrationNegative[i]) / (calibrationPositive[i] - calibrationNegative[i]);
} }
...@@ -520,36 +513,26 @@ void JoystickInput::setActiveJoystick(int id) ...@@ -520,36 +513,26 @@ void JoystickInput::setActiveJoystick(int id)
// Restore saved settings for this joystick. // Restore saved settings for this joystick.
loadJoystickSettings(); loadJoystickSettings();
qDebug() << "Roll: " << rollAxis << ", Pitch: " << pitchAxis << ", Yaw: " << yawAxis << ", Throttle: " << throttleAxis;
// Update cached joystick axes values. // Update cached joystick axes values.
// Also emit any signals for currently-triggering events // Also emit any signals for currently-triggering events
joystickAxes.clear(); joystickAxes.clear();
for (int i = 0; i < joystickNumAxes; i++) for (int i = 0; i < joystickNumAxes; i++)
{ {
int axisValue = SDL_JoystickGetAxis(joystick, i); joystickAxes.append(NAN);
joystickAxes.append(axisValue);
emit axisValueChanged(i, axisValue);
} }
// Update cached joystick button values. // Update cached joystick button values.
// Emit signals for any button events. // Emit signals for any button events.
joystickButtons = 0; 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 else
{ {
joystickNumButtons = 0; joystickNumButtons = 0;
joystickNumAxes = 0; joystickNumAxes = 0;
} }
emit joystickSettingsChanged();
} }
void JoystickInput::setAxisMapping(int axis, JOYSTICK_INPUT_MAPPING newMapping) void JoystickInput::setAxisMapping(int axis, JOYSTICK_INPUT_MAPPING newMapping)
......
...@@ -49,7 +49,7 @@ struct JoystickSettings { ...@@ -49,7 +49,7 @@ struct JoystickSettings {
QMap<int, bool> 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<int, bool> 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<int, int> buttonActions; ///< The index of the action associated with every button. QMap<int, int> buttonActions; ///< The index of the action associated with every button.
}; };
Q_DECLARE_METATYPE(JoystickSettings); Q_DECLARE_METATYPE(JoystickSettings)
/** /**
* @brief Joystick input * @brief Joystick input
...@@ -257,6 +257,11 @@ signals: ...@@ -257,6 +257,11 @@ signals:
*/ */
void hatDirectionChanged(int x, int y); 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. */ /** @brief Signals that new joystick-specific settings were changed. Useful for triggering updates that at dependent on the current joystick. */
void joystickSettingsChanged(); void joystickSettingsChanged();
......
...@@ -53,16 +53,9 @@ void JoystickAxis::setRangeLimit(bool newValue) ...@@ -53,16 +53,9 @@ void JoystickAxis::setRangeLimit(bool newValue)
void JoystickAxis::mappingComboBoxChanged(int newMapping) void JoystickAxis::mappingComboBoxChanged(int newMapping)
{ {
if (newMapping == JoystickInput::JOYSTICK_INPUT_MAPPING_THROTTLE) JoystickInput::JOYSTICK_INPUT_MAPPING mapping = (JoystickInput::JOYSTICK_INPUT_MAPPING)newMapping;
{ emit mappingChanged(id, mapping);
ui->rangeCheckBox->show(); updateUIBasedOnUAS(UASManager::instance()->getActiveUAS(), mapping);
}
else
{
ui->rangeCheckBox->hide();
}
emit mappingChanged(id, (JoystickInput::JOYSTICK_INPUT_MAPPING)newMapping);
this->setActiveUAS(UASManager::instance()->getActiveUAS());
} }
void JoystickAxis::inversionCheckBoxChanged(bool inverted) void JoystickAxis::inversionCheckBoxChanged(bool inverted)
...@@ -76,11 +69,17 @@ void JoystickAxis::rangeCheckBoxChanged(bool limited) ...@@ -76,11 +69,17 @@ void JoystickAxis::rangeCheckBoxChanged(bool limited)
} }
void JoystickAxis::setActiveUAS(UASInterface* uas) 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: // Set the throttle display to only positive if:
// * This is the throttle axis AND // * This is the throttle axis AND
// * The current UAS can't reverse OR there is no current UAS // * 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->progressBar->setRange(0, 100);
ui->rangeCheckBox->show(); ui->rangeCheckBox->show();
......
...@@ -38,6 +38,12 @@ public slots: ...@@ -38,6 +38,12 @@ public slots:
private: private:
int id; ///< The ID for this axis. Corresponds to the IDs used by JoystickInput. int id; ///< The ID for this axis. Corresponds to the IDs used by JoystickInput.
Ui::JoystickAxis *ui; 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: private slots:
/** @brief Handle changes to the mapping dropdown bar. */ /** @brief Handle changes to the mapping dropdown bar. */
......
...@@ -21,7 +21,7 @@ JoystickButton::~JoystickButton() ...@@ -21,7 +21,7 @@ JoystickButton::~JoystickButton()
void JoystickButton::setActiveUAS(UASInterface* uas) void JoystickButton::setActiveUAS(UASInterface* uas)
{ {
// Disable signals so that changes to joystickAction don't trigger JoystickInput updates. // 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) if (uas)
{ {
m_ui->joystickAction->setEnabled(true); m_ui->joystickAction->setEnabled(true);
...@@ -32,21 +32,23 @@ void JoystickButton::setActiveUAS(UASInterface* uas) ...@@ -32,21 +32,23 @@ void JoystickButton::setActiveUAS(UASInterface* uas)
{ {
m_ui->joystickAction->addItem(a->text()); m_ui->joystickAction->addItem(a->text());
} }
m_ui->joystickAction->setCurrentIndex(0);
} else { } else {
m_ui->joystickAction->setEnabled(false); m_ui->joystickAction->setEnabled(false);
m_ui->joystickAction->clear(); m_ui->joystickAction->clear();
m_ui->joystickAction->addItem("--"); 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) void JoystickButton::setAction(int index)
{ {
// Disable signals so that changes to joystickAction don't trigger JoystickInput updates. // 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. // Add one because the default no-action takes the 0-spot.
m_ui->joystickAction->setCurrentIndex(index + 1); m_ui->joystickAction->setCurrentIndex(index + 1);
//blockSignals(false); connect(m_ui->joystickAction, SIGNAL(currentIndexChanged(int)), this, SLOT(actionComboBoxChanged(int)));
} }
void JoystickButton::actionComboBoxChanged(int index) void JoystickButton::actionComboBoxChanged(int index)
......
...@@ -21,7 +21,8 @@ public: ...@@ -21,7 +21,8 @@ public:
public slots: public slots:
/** @brief Specify the UAS that this axis should track for displaying throttle properly. */ /** @brief Specify the UAS that this axis should track for displaying throttle properly. */
void setActiveUAS(UASInterface* uas); 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); void setAction(int index);
signals: signals:
......
...@@ -44,7 +44,7 @@ ...@@ -44,7 +44,7 @@
<item> <item>
<widget class="QLabel" name="joystickButtonLabel"> <widget class="QLabel" name="joystickButtonLabel">
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred"> <sizepolicy hsizetype="MinimumExpanding" vsizetype="Preferred">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
...@@ -69,7 +69,7 @@ ...@@ -69,7 +69,7 @@
<bool>false</bool> <bool>false</bool>
</property> </property>
<property name="sizePolicy"> <property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="Fixed"> <sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch> <horstretch>0</horstretch>
<verstretch>0</verstretch> <verstretch>0</verstretch>
</sizepolicy> </sizepolicy>
......
...@@ -3,7 +3,7 @@ ...@@ -3,7 +3,7 @@
#include "ui_JoystickWidget.h" #include "ui_JoystickWidget.h"
#include "JoystickButton.h" #include "JoystickButton.h"
#include "JoystickAxis.h" #include "JoystickAxis.h"
#include <QDebug>
#include <QDesktopWidget> #include <QDesktopWidget>
JoystickWidget::JoystickWidget(JoystickInput* joystick, QWidget *parent) : JoystickWidget::JoystickWidget(JoystickInput* joystick, QWidget *parent) :
...@@ -30,9 +30,8 @@ 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. // 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())); 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->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 // Initialize the UI to the current JoystickInput state. Also make sure to listen for future changes
// so that the UI can be updated. // so that the UI can be updated.
...@@ -109,13 +108,15 @@ void JoystickWidget::changeEvent(QEvent *e) ...@@ -109,13 +108,15 @@ void JoystickWidget::changeEvent(QEvent *e)
void JoystickWidget::updateUI() void JoystickWidget::updateUI()
{ {
// Update the actions for all of the buttons
for (int i = 0; i < buttons.size(); i++) for (int i = 0; i < buttons.size(); i++)
{ {
JoystickButton* button = buttons[i]; JoystickButton* button = buttons[i];
int action = joystick->getActionForButton(i); int action = joystick->getActionForButton(i);
button->setAction(action + 1); button->setAction(action);
qDebug() << "JoystickWidget: Updating button " << i << " to action " << action + 1;
} }
// Update the axis mappings
int rollAxis = joystick->getMappingRollAxis(); int rollAxis = joystick->getMappingRollAxis();
int pitchAxis = joystick->getMappingPitchAxis(); int pitchAxis = joystick->getMappingPitchAxis();
int yawAxis = joystick->getMappingYawAxis(); int yawAxis = joystick->getMappingYawAxis();
...@@ -147,7 +148,6 @@ void JoystickWidget::updateUI() ...@@ -147,7 +148,6 @@ void JoystickWidget::updateUI()
axis->setInverted(inverted); axis->setInverted(inverted);
bool limited = joystick->getRangeLimitForAxis(i); bool limited = joystick->getRangeLimitForAxis(i);
axis->setRangeLimit(limited); axis->setRangeLimit(limited);
qDebug() << "JoystickWidget: Updating axis " << i << " to value:" << value << ", mapping:" << mapping << ", inverted:" << inverted << ", limited:" << limited;
} }
} }
...@@ -175,7 +175,7 @@ void JoystickWidget::createUIForJoystick() ...@@ -175,7 +175,7 @@ void JoystickWidget::createUIForJoystick()
JoystickButton* button = new JoystickButton(i, m_ui->buttonBox); JoystickButton* button = new JoystickButton(i, m_ui->buttonBox);
button->setAction(joystick->getActionForButton(i)); button->setAction(joystick->getActionForButton(i));
connect(button, SIGNAL(actionChanged(int,int)), this->joystick, SLOT(setButtonAction(int,int))); 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); m_ui->buttonLayout->addWidget(button);
buttons.append(button); buttons.append(button);
} }
...@@ -218,7 +218,7 @@ void JoystickWidget::createUIForJoystick() ...@@ -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(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(inversionChanged(int,bool)), this->joystick, SLOT(setAxisInversion(int,bool)));
connect(axis, SIGNAL(rangeChanged(int,bool)), this->joystick, SLOT(setAxisRangeLimit(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); m_ui->axesLayout->addWidget(axis);
axes.append(axis); axes.append(axis);
} }
......
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