diff --git a/files/styles/style-dark.css b/files/styles/style-dark.css index af8a6407964de3f89adc7755d023d5d1c4a0d178..0e04d607fd9d548a71bfe2bc99d1522236e229ae 100644 --- a/files/styles/style-dark.css +++ b/files/styles/style-dark.css @@ -9,6 +9,13 @@ color: #777; } +JoystickButton QLabel { + border: 1px solid #AAA; + border-radius: 4px; + height: 16px; + padding: 0 3px; +} + QCheckBox { color: #DDD; } @@ -228,7 +235,8 @@ QLabel { } QLabel:disabled { - color: #353535; + color: #444; + border-color: #444; } QLabel#noUas { diff --git a/files/styles/style-light.css b/files/styles/style-light.css index 0db9cd0cafbddd0ac5e4f44703d2d21cb0292acc..25c38addf4d8854ad865f695abcf67fb55f95174 100644 --- a/files/styles/style-light.css +++ b/files/styles/style-light.css @@ -9,6 +9,13 @@ color: #AAA; } +JoystickButton QLabel { + border: 1px solid #777; + border-radius: 4px; + height: 16px; + padding: 0 3px; +} + QCheckBox { color: #222; } @@ -228,7 +235,8 @@ QLabel { } QLabel:disabled { - color: #AAA; + color: #999; + border-color: #999; } QLabel#noUas { diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index b14b56de500462278d7d40d38458e3d555096eef..e6bf41d23b215e7df467a8bdf904ff0de53e0bf2 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -234,7 +234,9 @@ FORMS += src/ui/MainWindow.ui \ src/ui/uas/UASActionsWidget.ui \ src/ui/QGCTabbedInfoView.ui \ src/ui/UASRawStatusView.ui \ - src/ui/uas/QGCMessageView.ui + src/ui/uas/QGCMessageView.ui \ + src/ui/JoystickButton.ui \ + src/ui/JoystickAxis.ui INCLUDEPATH += src \ src/ui \ src/ui/linechart \ @@ -392,7 +394,9 @@ HEADERS += src/MG.h \ src/ui/QGCTabbedInfoView.h \ src/ui/UASRawStatusView.h \ src/ui/PrimaryFlightDisplay.h \ - src/ui/uas/QGCMessageView.h + src/ui/uas/QGCMessageView.h \ + src/ui/JoystickButton.h \ + src/ui/JoystickAxis.h # Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::HEADERS += src/ui/map3D/QGCGoogleEarthView.h @@ -568,7 +572,9 @@ SOURCES += src/main.cc \ src/ui/QGCTabbedInfoView.cpp \ src/ui/UASRawStatusView.cpp \ src/ui/PrimaryFlightDisplay.cpp \ - src/ui/uas/QGCMessageView.cc + src/ui/uas/QGCMessageView.cc \ + src/ui/JoystickButton.cc \ + src/ui/JoystickAxis.cc # Enable Google Earth only on Mac OS and Windows with Visual Studio compiler macx|macx-g++|macx-g++42|win32-msvc2008|win32-msvc2010|win32-msvc2012::SOURCES += src/ui/map3D/QGCGoogleEarthView.cc diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index a24e896ab435b65efb51526d8287921190eb5764..a75042bf372b60a214ac80d6f3877fbc5c781e52 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -855,10 +855,7 @@ void MAVLinkSimulationLink::writeBytes(const char* data, qint64 size) break; } } - unsigned char v=data[i]; - fprintf(stderr,"%02x ", v); } - fprintf(stderr,"\n"); readyBufferMutex.lock(); for (int i = 0; i < streampointer; i++) diff --git a/src/comm/MAVLinkSimulationMAV.cc b/src/comm/MAVLinkSimulationMAV.cc index 6efd8ff5b72276490d236bf371c9b7bc117ff72b..2f575eff73ac3d093c132dce00ecbd424b69e207 100644 --- a/src/comm/MAVLinkSimulationMAV.cc +++ b/src/comm/MAVLinkSimulationMAV.cc @@ -382,11 +382,11 @@ static void print_message(const mavlink_message_t *msg) const mavlink_message_info_t *m = &message_info[msg->msgid]; const mavlink_field_info_t *f = m->fields; unsigned i; - qDebug("%s { ", m->name); - for (i=0; inum_fields; i++) { - print_field(msg, &f[i]); - } - qDebug("}\n"); +// qDebug("%s { ", m->name); +// for (i=0; inum_fields; i++) { +// print_field(msg, &f[i]); +// } +// qDebug("}\n"); } void MAVLinkSimulationMAV::handleMessage(const mavlink_message_t& msg) diff --git a/src/input/JoystickInput.cc b/src/input/JoystickInput.cc index 074e3c1a753288ec7cadd3828f7a2ea83203dd1d..7f1bc7d7e8bb0deec4b84e9242e087d248389412 100644 --- a/src/input/JoystickInput.cc +++ b/src/input/JoystickInput.cc @@ -19,81 +19,252 @@ #include "QGC.h" #include #include +#include +#include + +using namespace std; /** * The coordinate frame of the joystick axis is the aeronautical frame like shown on this image: * @image html http://pixhawk.ethz.ch/wiki/_media/standards/body-frame.png Aeronautical frame */ JoystickInput::JoystickInput() : - sdlJoystickMin(-32768.0f), - sdlJoystickMax(32767.0f), - defaultIndex(0), - uas(NULL), - uasButtonList(QList()), - done(false), - thrustAxis(2), - xAxis(0), - yAxis(1), - yawAxis(3), - autoButtonMapping(-1), - manualButtonMapping(-1), - stabilizeButtonMapping(-1), - joystickName(tr("Unitinialized")) + sdlJoystickMin(-32768.0f), + sdlJoystickMax(32767.0f), + isEnabled(false), + done(false), + uas(NULL), + autopilotType(0), + systemType(0), + uasCanReverse(false), + rollAxis(-1), + pitchAxis(-1), + yawAxis(-1), + throttleAxis(-1), + joystickName(""), + joystickID(-1), + joystickNumButtons(0) { - loadSettings(); for (int i = 0; i < 10; i++) { calibrationPositive[i] = sdlJoystickMax; calibrationNegative[i] = sdlJoystickMin; } - connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); + // Make sure we initialize with the correct UAS. + setActiveUAS(UASManager::instance()->getActiveUAS()); - // Enter main loop - //start(); + // Start this thread. This allows the Joystick Settings window to work correctly even w/o any UASes connected. + start(); } JoystickInput::~JoystickInput() { - storeSettings(); + storeGeneralSettings(); + storeJoystickSettings(); done = true; } -void JoystickInput::loadSettings() +void JoystickInput::loadGeneralSettings() { // Load defaults from settings QSettings settings; settings.sync(); - settings.beginGroup("QGC_JOYSTICK_INPUT"); - xAxis = (settings.value("X_AXIS_MAPPING", xAxis).toInt()); - yAxis = (settings.value("Y_AXIS_MAPPING", yAxis).toInt()); - thrustAxis = (settings.value("THRUST_AXIS_MAPPING", thrustAxis).toInt()); - yawAxis = (settings.value("YAW_AXIS_MAPPING", yawAxis).toInt()); - autoButtonMapping = (settings.value("AUTO_BUTTON_MAPPING", autoButtonMapping).toInt()); - stabilizeButtonMapping = (settings.value("STABILIZE_BUTTON_MAPPING", stabilizeButtonMapping).toInt()); - manualButtonMapping = (settings.value("MANUAL_BUTTON_MAPPING", manualButtonMapping).toInt()); + + // Deal with settings specific to the JoystickInput + settings.beginGroup("JOYSTICK_INPUT"); + isEnabled = settings.value("ENABLED", false).toBool(); + joystickName = settings.value("JOYSTICK_NAME", "").toString(); + settings.endGroup(); +} + +/** + * @brief Restores settings for the current joystick from saved settings file. + * Assumes that both joystickName & joystickNumAxes are correct. + */ +void JoystickInput::loadJoystickSettings() +{ + // Load defaults from settings + QSettings settings; + settings.sync(); + + // Now for the current joystick + settings.beginGroup(joystickName); + rollAxis = (settings.value("ROLL_AXIS_MAPPING", -1).toInt()); + pitchAxis = (settings.value("PITCH_AXIS_MAPPING", -1).toInt()); + yawAxis = (settings.value("YAW_AXIS_MAPPING", -1).toInt()); + throttleAxis = (settings.value("THROTTLE_AXIS_MAPPING", -1).toInt()); + + // Clear out and then restore the (AUTOPILOT, SYSTEM) mapping for joystick settings + joystickSettings.clear(); + int autopilots = settings.beginReadArray("AUTOPILOTS"); + for (int i = 0; i < autopilots; i++) + { + settings.setArrayIndex(i); + int autopilotType = settings.value("AUTOPILOT_TYPE", 0).toInt(); + int systems = settings.beginReadArray("SYSTEMS"); + for (int j = 0; j < systems; j++) + { + settings.setArrayIndex(j); + int systemType = settings.value("SYSTEM_TYPE", 0).toInt(); + + // Now that both the autopilot and system type are available, update some references. + QMap* joystickAxesInverted = &joystickSettings[autopilotType][systemType].axesInverted; + QMap* joystickAxesLimited = &joystickSettings[autopilotType][systemType].axesLimited; + QMap* joystickButtonActions = &joystickSettings[autopilotType][systemType].buttonActions; + + // Read back the joystickAxesInverted QList one element at a time. + int axesStored = settings.beginReadArray("AXES_INVERTED"); + for (int k = 0; k < axesStored; k++) + { + settings.setArrayIndex(k); + int index = settings.value("INDEX", 0).toInt(); + bool inverted = settings.value("INVERTED", false).toBool(); + joystickAxesInverted->insert(index, inverted); + } + settings.endArray(); + + // Read back the joystickAxesLimited QList one element at a time. + axesStored = settings.beginReadArray("AXES_LIMITED"); + for (int k = 0; k < axesStored; k++) + { + settings.setArrayIndex(k); + int index = settings.value("INDEX", 0).toInt(); + bool limited = settings.value("LIMITED", false).toBool(); + joystickAxesLimited->insert(index, limited); + } + settings.endArray(); + + // Read back the button->action mapping. + int buttonsStored = settings.beginReadArray("BUTTONS_ACTIONS"); + for (int k = 0; k < buttonsStored; k++) + { + settings.setArrayIndex(k); + int index = settings.value("INDEX", 0).toInt(); + int action = settings.value("ACTION", 0).toInt(); + joystickButtonActions->insert(index, action); + } + settings.endArray(); + } + settings.endArray(); + } + settings.endArray(); + settings.endGroup(); + + emit joystickSettingsChanged(); } -void JoystickInput::storeSettings() +void JoystickInput::storeGeneralSettings() const +{ + QSettings settings; + settings.beginGroup("JOYSTICK_INPUT"); + settings.setValue("ENABLED", isEnabled); + settings.setValue("JOYSTICK_NAME", joystickName); + settings.endGroup(); + settings.sync(); +} + +void JoystickInput::storeJoystickSettings() const { // Store settings QSettings settings; - settings.beginGroup("QGC_JOYSTICK_INPUT"); - settings.setValue("X_AXIS_MAPPING", xAxis); - settings.setValue("Y_AXIS_MAPPING", yAxis); - settings.setValue("THRUST_AXIS_MAPPING", thrustAxis); + settings.beginGroup(joystickName); + settings.setValue("ROLL_AXIS_MAPPING", rollAxis); + settings.setValue("PITCH_AXIS_MAPPING", pitchAxis); settings.setValue("YAW_AXIS_MAPPING", yawAxis); - settings.setValue("AUTO_BUTTON_MAPPING", autoButtonMapping); - settings.setValue("STABILIZE_BUTTON_MAPPING", stabilizeButtonMapping); - settings.setValue("MANUAL_BUTTON_MAPPING", manualButtonMapping); + settings.setValue("THROTTLE_AXIS_MAPPING", throttleAxis); + settings.beginWriteArray("AUTOPILOTS"); + QMapIterator > i(joystickSettings); + int autopilotIndex = 0; + while (i.hasNext()) + { + i.next(); + settings.setArrayIndex(autopilotIndex++); + + int autopilotType = i.key(); + settings.setValue("AUTOPILOT_TYPE", autopilotType); + + settings.beginWriteArray("SYSTEMS"); + QMapIterator j(i.value()); + int systemIndex = 0; + while (j.hasNext()) + { + j.next(); + settings.setArrayIndex(systemIndex++); + + int systemType = j.key(); + settings.setValue("SYSTEM_TYPE", systemType); + + // Now that both the autopilot and system type are available, update some references. + QMapIterator joystickAxesInverted(joystickSettings[autopilotType][systemType].axesInverted); + QMapIterator joystickAxesLimited(joystickSettings[autopilotType][systemType].axesLimited); + QMapIterator joystickButtonActions(joystickSettings[autopilotType][systemType].buttonActions); + + settings.beginWriteArray("AXES_INVERTED"); + int k = 0; + while (joystickAxesInverted.hasNext()) + { + joystickAxesInverted.next(); + int inverted = joystickAxesInverted.value(); + // Only save this axes' inversion status if it's not the default + if (inverted) + { + settings.setArrayIndex(k++); + int index = joystickAxesInverted.key(); + settings.setValue("INDEX", index); + settings.setValue("INVERTED", inverted); + } + } + settings.endArray(); + + settings.beginWriteArray("AXES_LIMITED"); + k = 0; + while (joystickAxesLimited.hasNext()) + { + joystickAxesLimited.next(); + int limited = joystickAxesLimited.value(); + if (limited) + { + settings.setArrayIndex(k++); + int index = joystickAxesLimited.key(); + settings.setValue("INDEX", index); + settings.setValue("LIMITED", limited); + } + } + settings.endArray(); + + settings.beginWriteArray("BUTTONS_ACTIONS"); + k = 0; + while (joystickButtonActions.hasNext()) + { + joystickButtonActions.next(); + int action = joystickButtonActions.value(); + if (action != -1) + { + settings.setArrayIndex(k++); + int index = joystickButtonActions.key(); + settings.setValue("INDEX", index); + settings.setValue("ACTION", action); + } + } + settings.endArray(); + } + settings.endArray(); // SYSTEMS + } + settings.endArray(); // AUTOPILOTS settings.endGroup(); settings.sync(); } - void JoystickInput::setActiveUAS(UASInterface* uas) { + // Do nothing if the UAS hasn't changed. + if (uas == this->uas) + { + return; + } + // Only connect / disconnect is the UAS is of a controllable UAS class UAS* tmp = 0; if (this->uas) @@ -102,65 +273,101 @@ void JoystickInput::setActiveUAS(UASInterface* uas) if(tmp) { disconnect(this, SIGNAL(joystickChanged(double,double,double,double,int,int,int)), tmp, SLOT(setManualControlCommands(double,double,double,double,int,int,int))); - disconnect(this, SIGNAL(buttonPressed(int)), tmp, SLOT(receiveButton(int))); + disconnect(this, SIGNAL(actionTriggered(int)), tmp, SLOT(triggerAction(int))); } + uasCanReverse = false; + } + + // Save any settings for the last UAS + if (joystickID > -1) + { + storeJoystickSettings(); } this->uas = uas; - tmp = dynamic_cast(this->uas); - if(tmp) { + if (this->uas && (tmp = dynamic_cast(this->uas))) + { connect(this, SIGNAL(joystickChanged(double,double,double,double,int,int,int)), tmp, SLOT(setManualControlCommands(double,double,double,double,int,int,int))); - connect(this, SIGNAL(buttonPressed(int)), tmp, SLOT(receiveButton(int))); + connect(this, SIGNAL(actionTriggered(int)), tmp, SLOT(triggerAction(int))); + uasCanReverse = tmp->systemCanReverse(); + + // Update the joystick settings for a new UAS. + autopilotType = uas->getAutopilotType(); + systemType = uas->getSystemType(); } - if (!isRunning()) + + // 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) { - start(); + loadJoystickSettings(); } } +void JoystickInput::setEnabled(bool enabled) +{ + this->isEnabled = enabled; + storeJoystickSettings(); +} + void JoystickInput::init() { - // INITIALIZE SDL Joystick support + // Initialize SDL Joystick support and detect number of joysticks. if (SDL_InitSubSystem(SDL_INIT_JOYSTICK | SDL_INIT_NOPARACHUTE) < 0) { printf("Couldn't initialize SimpleDirectMediaLayer: %s\n", SDL_GetError()); } // Enumerate joysticks and select one - int numJoysticks = SDL_NumJoysticks(); + numJoysticks = SDL_NumJoysticks(); - // Wait for joysticks if none is connected - while (numJoysticks == 0 && !done) + // If no joysticks are connected, there's nothing we can do, so just keep + // going back to sleep every second unless the program quits. + while (!numJoysticks && !done) { - QGC::SLEEP::msleep(400); - // INITIALIZE SDL Joystick support - if (SDL_InitSubSystem(SDL_INIT_JOYSTICK | SDL_INIT_NOPARACHUTE) < 0) - { - printf("Couldn't initialize SimpleDirectMediaLayer: %s\n", SDL_GetError()); - } - numJoysticks = SDL_NumJoysticks(); + QGC::SLEEP::sleep(1); } if (done) { return; } - printf("%d Input devices found:\n", numJoysticks); - for(int i=0; i < SDL_NumJoysticks(); i++ ) + // Now that we've detected a joystick, load in the joystick-agnostic settings. + loadGeneralSettings(); + + // Enumerate all found devices + qDebug() << QString("%1 Input devices found:").arg(numJoysticks); + int activeJoystick = 0; + for(int i=0; i < numJoysticks; i++ ) { - printf("\t- %s\n", SDL_JoystickName(i)); - joystickName = QString(SDL_JoystickName(i)); - } + QString name = SDL_JoystickName(i); + qDebug() << QString("\t%1").arg(name); - printf("\nOpened %s\n", SDL_JoystickName(defaultIndex)); + // 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. + if (name == joystickName) + { + activeJoystick = i; + } - SDL_JoystickEventState(SDL_ENABLE); + SDL_Joystick* x = SDL_JoystickOpen(i); + 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); + } - joystick = SDL_JoystickOpen(defaultIndex); + // Set the active joystick based on name, if a joystick was found in the saved settings, otherwise + // default to the first one. + setActiveJoystick(activeJoystick); - // Make sure active UAS is set + // Now make sure we know what the current UAS is and track changes to it. setActiveUAS(UASManager::instance()->getActiveUAS()); + connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); } + void JoystickInput::shutdown() { done = true; @@ -168,6 +375,8 @@ void JoystickInput::shutdown() /** * @brief Execute the Joystick process + * Note that the SDL procedure is polled. This is because connecting and disconnecting while the event checker is running + * fails as of SDL 1.2. It is therefore much easier to just poll for the joystick we want to sample. */ void JoystickInput::run() { @@ -181,150 +390,250 @@ void JoystickInput::run() exit(); return; } - while(SDL_PollEvent(&event)) - { - - SDL_JoystickUpdate(); - - // Todo check if it would be more beneficial to use the event structure - switch(event.type) { - case SDL_KEYDOWN: - /* handle keyboard stuff here */ - //qDebug() << "KEY PRESSED!"; - break; - case SDL_QUIT: - /* Set whatever flags are necessary to */ - /* end the main loop here */ - break; + // Poll the joystick for new values. + SDL_JoystickUpdate(); - case SDL_JOYBUTTONDOWN: /* Handle Joystick Button Presses */ - if ( event.jbutton.button == 0 ) { - //qDebug() << "BUTTON PRESSED!"; - } - break; - - case SDL_JOYAXISMOTION: /* Handle Joystick Motion */ - if ( ( event.jaxis.value < -3200 ) || (event.jaxis.value > 3200 ) ) { - if( event.jaxis.axis == 0) { - /* Left-right movement code goes here */ - } + // Emit all necessary signals for all axes. + for (int i = 0; i < joystickNumAxes; i++) + { + // First emit the uncalibrated values for each axis based on their ID. + // 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].axesInverted[i]) + { + axisValue = (axisValue - calibrationNegative[i]) / (calibrationPositive[i] - calibrationNegative[i]); + } + else + { + axisValue = (axisValue - calibrationPositive[i]) / (calibrationNegative[i] - calibrationPositive[i]); + } + axisValue = 1.0f - axisValue; - if( event.jaxis.axis == 1) { - /* Up-Down movement code goes here */ - } + // For non-throttle axes or if the UAS can reverse, go ahead and convert this into the range [-1:1]. + if (uasCanReverse || throttleAxis != i) + { + axisValue = axisValue * 2.0f - 1.0f; + } + // Otherwise if this vehicle can only go forward, but the axis is limited to only the positive range, + // scale this so the negative values are ignored for this axis and it's clamped to [0:1]. + else if (throttleAxis == i && joystickSettings[autopilotType][systemType].axesLimited.value(i)) + { + axisValue = axisValue * 2.0f - 1.0f; + if (axisValue < 0.0f) + { + axisValue = 0.0f; } - break; + } - default: - //qDebug() << "SDL event occured"; - break; + // Bound rounding errors + if (axisValue > 1.0f) axisValue = 1.0f; + if (axisValue < -1.0f) axisValue = -1.0f; + if (joystickAxes[i] != axisValue) + { + joystickAxes[i] = axisValue; + emit axisValueChanged(i, axisValue); } } -// // Display all axes -// for(int i = 0; i < SDL_JoystickNumAxes(joystick); i++) -// { -// qDebug() << "\rAXIS" << i << "is: " << SDL_JoystickGetAxis(joystick, i); -// } - - // THRUST - double thrust = ((double)SDL_JoystickGetAxis(joystick, thrustAxis) - calibrationNegative[thrustAxis]) / (calibrationPositive[thrustAxis] - calibrationNegative[thrustAxis]); - // Has to be inverted for Logitech Wingman - thrust = 1.0f - thrust; - thrust = thrust * 2.0f - 1.0f; - // Bound rounding errors - if (thrust > 1.0f) thrust = 1.0f; - if (thrust < -1.0f) thrust = -1.0f; - emit thrustChanged((float)thrust); - - // X Axis - double x = ((double)SDL_JoystickGetAxis(joystick, xAxis) - calibrationNegative[xAxis]) / (calibrationPositive[xAxis] - calibrationNegative[xAxis]); - x = 1.0f - x; - x = x * 2.0f - 1.0f; - // Bound rounding errors - if (x > 1.0f) x = 1.0f; - if (x < -1.0f) x = -1.0f; - emit xChanged((float)x); - - // Y Axis - double y = ((double)SDL_JoystickGetAxis(joystick, yAxis) - calibrationNegative[yAxis]) / (calibrationPositive[yAxis] - calibrationNegative[yAxis]); - y = 1.0f - y; - y = y * 2.0f - 1.0f; - // Bound rounding errors - if (y > 1.0f) y = 1.0f; - if (y < -1.0f) y = -1.0f; - emit yChanged((float)y); - - // Yaw Axis - - double yaw = ((double)SDL_JoystickGetAxis(joystick, yawAxis) - calibrationNegative[yawAxis]) / (calibrationPositive[yawAxis] - calibrationNegative[yawAxis]); - yaw = 1.0f - yaw; - yaw = yaw * 2.0f - 1.0f; - // Bound rounding errors - if (yaw > 1.0f) yaw = 1.0f; - if (yaw < -1.0f) yaw = -1.0f; - emit yawChanged((float)yaw); - - // Get joystick hat position, convert it to vector + // Build up vectors describing the hat position int hatPosition = SDL_JoystickGetHat(joystick, 0); + int newYHat = 0; + if ((SDL_HAT_UP & hatPosition) > 0) newYHat = 1; + if ((SDL_HAT_DOWN & hatPosition) > 0) newYHat = -1; + int newXHat = 0; + if ((SDL_HAT_LEFT & hatPosition) > 0) newXHat = -1; + if ((SDL_HAT_RIGHT & hatPosition) > 0) newXHat = 1; + if (newYHat != yHat || newXHat != xHat) + { + xHat = newXHat; + yHat = newYHat; + emit hatDirectionChanged(newXHat, newYHat); + } - int xHat,yHat; - xHat = 0; - yHat = 0; - - // Build up vectors describing the hat position - // - // Coordinate frame for joystick hat: - // - // y - // ^ - // | - // | - // 0 ----> x - // - - if ((SDL_HAT_UP & hatPosition) > 0) yHat = 1; - if ((SDL_HAT_DOWN & hatPosition) > 0) yHat = -1; - - if ((SDL_HAT_LEFT & hatPosition) > 0) xHat = -1; - if ((SDL_HAT_RIGHT & hatPosition) > 0) xHat = 1; - - // Send new values to rest of groundstation - emit hatDirectionChanged(xHat, yHat); - - // Display all buttons - int buttons = 0; - for(int i = 0; i < SDL_JoystickNumButtons(joystick); i++) + // Emit signals for each button individually + for (int i = 0; i < joystickNumButtons; i++) { - //qDebug() << "BUTTON" << i << "is: " << SDL_JoystickGetAxis(joystick, i); - if(SDL_JoystickGetButton(joystick, i)) + // If the button was down, but now it's up, trigger a buttonPressed event + quint16 lastButtonState = joystickButtons & (1 << i); + if (SDL_JoystickGetButton(joystick, i) && !lastButtonState) { emit buttonPressed(i); - buttons |= 1 << i; - // Check if button is a UAS select button - - if (uasButtonList.contains(i)) + joystickButtons |= 1 << i; + } + else if (!SDL_JoystickGetButton(joystick, i) && lastButtonState) + { + emit buttonReleased(i); + if (isEnabled && joystickSettings[autopilotType][systemType].buttonActions.contains(i)) { - UASInterface* uas = UASManager::instance()->getUASForId(i); - if (uas) - { - UASManager::instance()->setActiveUAS(uas); - } + emit actionTriggered(joystickSettings[autopilotType][systemType].buttonActions.value(i)); } + joystickButtons &= ~(1 << i); } + } + // Now signal an update for all UI together. + if (isEnabled) + { + float roll = rollAxis > -1?joystickAxes[rollAxis]:numeric_limits::quiet_NaN(); + float pitch = pitchAxis > -1?joystickAxes[pitchAxis]:numeric_limits::quiet_NaN(); + float yaw = yawAxis > -1?joystickAxes[yawAxis]:numeric_limits::quiet_NaN(); + float throttle = throttleAxis > -1?joystickAxes[throttleAxis]:numeric_limits::quiet_NaN(); + emit joystickChanged(roll, pitch, yaw, throttle, xHat, yHat, joystickButtons); } - emit joystickChanged(y, x, yaw, thrust, xHat, yHat, buttons); // Sleep, update rate of joystick is approx. 50 Hz (1000 ms / 50 = 20 ms) QGC::SLEEP::msleep(20); + } +} +void JoystickInput::setActiveJoystick(int id) +{ + // If we already had a joystick, close that one before opening a new one. + if (joystick && SDL_JoystickOpened(joystickID)) + { + storeJoystickSettings(); + SDL_JoystickClose(joystick); + joystick = NULL; + joystickID = -1; } + joystickID = id; + joystick = SDL_JoystickOpen(joystickID); + if (joystick && SDL_JoystickOpened(joystickID)) + { + // Update joystick configuration. + joystickName = QString(SDL_JoystickName(joystickID)); + joystickNumButtons = SDL_JoystickNumButtons(joystick); + joystickNumAxes = SDL_JoystickNumAxes(joystick); + + // Restore saved settings for this joystick. + loadJoystickSettings(); + + // Update cached joystick axes values. + // Also emit any signals for currently-triggering events + joystickAxes.clear(); + for (int i = 0; i < joystickNumAxes; i++) + { + joystickAxes.append(numeric_limits::quiet_NaN()); + } + + // Update cached joystick button values. + // Emit signals for any button events. + joystickButtons = 0; + } + else + { + joystickNumButtons = 0; + joystickNumAxes = 0; + } + + // Specify that a new joystick has been selected, so that any UI elements can update. + emit newJoystickSelected(); + // And then trigger an update of this new UI. + emit joystickSettingsChanged(); } -const QString& JoystickInput::getName() +void JoystickInput::setAxisMapping(int axis, JOYSTICK_INPUT_MAPPING newMapping) { - return joystickName; + switch (newMapping) + { + case JOYSTICK_INPUT_MAPPING_ROLL: + rollAxis = axis; + break; + case JOYSTICK_INPUT_MAPPING_PITCH: + pitchAxis = axis; + break; + case JOYSTICK_INPUT_MAPPING_YAW: + yawAxis = axis; + break; + case JOYSTICK_INPUT_MAPPING_THROTTLE: + throttleAxis = axis; + break; + case JOYSTICK_INPUT_MAPPING_NONE: + default: + if (rollAxis == axis) + { + rollAxis = -1; + } + if (pitchAxis == axis) + { + pitchAxis = -1; + } + if (yawAxis == axis) + { + yawAxis = -1; + } + if (throttleAxis == axis) + { + throttleAxis = -1; + joystickSettings[autopilotType][systemType].axesLimited.remove(axis); + } + break; + } + storeJoystickSettings(); +} + +void JoystickInput::setAxisInversion(int axis, bool inverted) +{ + if (axis < joystickNumAxes) + { + joystickSettings[autopilotType][systemType].axesInverted[axis] = inverted; + storeJoystickSettings(); + } +} + +void JoystickInput::setAxisRangeLimit(int axis, bool limitRange) +{ + if (axis < joystickNumAxes) + { + joystickSettings[autopilotType][systemType].axesLimited[axis] = limitRange; + storeJoystickSettings(); + } +} + +void JoystickInput::setButtonAction(int button, int action) +{ + if (button < joystickNumButtons) + { + joystickSettings[autopilotType][systemType].buttonActions[button] = action; + storeJoystickSettings(); + } +} + +float JoystickInput::getCurrentValueForAxis(int axis) const +{ + if (axis < joystickNumAxes) + { + return joystickAxes.at(axis); + } + return 0.0f; +} + +bool JoystickInput::getInvertedForAxis(int axis) const +{ + if (axis < joystickNumAxes) + { + return joystickSettings[autopilotType][systemType].axesInverted.value(axis); + } + return false; +} + +bool JoystickInput::getRangeLimitForAxis(int axis) const +{ + if (axis < joystickNumAxes) + { + return joystickSettings[autopilotType][systemType].axesLimited.value(axis); + } + return false; +} + +int JoystickInput::getActionForButton(int button) const +{ + if (button < joystickNumButtons && joystickSettings[autopilotType][systemType].buttonActions.contains(button)) + { + return joystickSettings[autopilotType][systemType].buttonActions.value(button); + } + return -1; } diff --git a/src/input/JoystickInput.h b/src/input/JoystickInput.h index 6315b55e9cc117e7fa02c69e4bc1c3150f920dd2..66070990d2e36e07203b27ef83c7eb2e6bbc9dc3 100644 --- a/src/input/JoystickInput.h +++ b/src/input/JoystickInput.h @@ -23,11 +23,20 @@ This file is part of the PIXHAWK project /** * @file - * @brief Definition of joystick interface + * @brief Definition of joystick interface * - * @author Lorenz Meier - * @author Andreas Romer + * This class defines a new thread to operate the reading of any joystick/controllers + * via the Simple Directmedia Library (libsdl.org). This relies on polling of the SDL, + * which is not their recommended method, instead they suggest use event checking. That + * does not seem to support switching joysticks after their internal event loop has started, + * so it was abandoned. * + * All joystick-related functionality is done in this class, though the JoystickWidget provides + * a UI around modifying its settings. Additionally controller buttons can be mapped to + * actions defined by any UASInterface object through the `UASInterface::getActions()` function. + * + * @author Lorenz Meier + * @author Andreas Romer */ #ifndef _JOYSTICKINPUT_H_ @@ -44,6 +53,13 @@ This file is part of the PIXHAWK project #include "UASInterface.h" +struct JoystickSettings { + QMap axesInverted; ///< Whether each axis should be used inverted from what was reported. + 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) + /** * @brief Joystick input */ @@ -53,81 +69,147 @@ class JoystickInput : public QThread public: JoystickInput(); - ~JoystickInput(); + ~JoystickInput(); void run(); void shutdown(); - const QString& getName(); + /** + * @brief The JOYSTICK_INPUT_MAPPING enum storing the values for each item in the mapping combobox. + * This should match the order of items in the mapping combobox in JoystickAxis.ui. + */ + enum JOYSTICK_INPUT_MAPPING + { + JOYSTICK_INPUT_MAPPING_NONE = 0, + JOYSTICK_INPUT_MAPPING_YAW = 1, + JOYSTICK_INPUT_MAPPING_PITCH = 2, + JOYSTICK_INPUT_MAPPING_ROLL = 3, + JOYSTICK_INPUT_MAPPING_THROTTLE = 4 + }; /** - * @brief Load joystick settings + * @brief Load joystick-specific settings. + */ + void loadJoystickSettings(); + /** + * @brief Load joystick-independent settings. */ - void loadSettings(); + void loadGeneralSettings(); /** - * @brief Store joystick settings + * @brief Store joystick-specific settings. + */ + void storeJoystickSettings() const; + /** + * @brief Store joystick-independent settings. */ - void storeSettings(); + void storeGeneralSettings() const; - int getMappingThrustAxis() + bool enabled() const { - return thrustAxis; + return isEnabled; } - int getMappingXAxis() + int getMappingThrottleAxis() const { - return xAxis; + return throttleAxis; } - int getMappingYAxis() + int getMappingRollAxis() const { - return yAxis; + return rollAxis; } - int getMappingYawAxis() + int getMappingPitchAxis() const + { + return pitchAxis; + } + + int getMappingYawAxis() const { return yawAxis; } - int getMappingAutoButton() + int getJoystickNumButtons() const { - return autoButtonMapping; + return joystickNumButtons; } - int getMappingManualButton() + int getJoystickNumAxes() const { - return manualButtonMapping; + return joystickNumAxes; } - int getMappingStabilizeButton() + int getJoystickID() const { - return stabilizeButtonMapping; + return joystickID; } + const QString& getName() const + { + return joystickName; + } + + int getNumJoysticks() const + { + return numJoysticks; + } + + QString getJoystickNameById(int id) const + { + return QString(SDL_JoystickName(id)); + } + + float getCurrentValueForAxis(int axis) const; + bool getInvertedForAxis(int axis) const; + bool getRangeLimitForAxis(int axis) const; + int getActionForButton(int button) const; + const double sdlJoystickMin; const double sdlJoystickMax; protected: - int defaultIndex; double calibrationPositive[10]; double calibrationNegative[10]; - SDL_Joystick* joystick; - UASInterface* uas; - QList uasButtonList; + + bool isEnabled; ///< Track whether the system should emit the higher-level signals: joystickChanged & actionTriggered. bool done; - QMutex m_doneMutex; - // Axis 3 is thrust (CALIBRATION!) - int thrustAxis; - int xAxis; - int yAxis; + SDL_Joystick* joystick; + UASInterface* uas; ///< Track the current UAS. + int autopilotType; ///< Cache the autopilotType + int systemType; ///< Cache the systemType + bool uasCanReverse; ///< Track whether the connect UAS can drive a reverse speed. + + // Store the mapping between axis numbers and the roll/pitch/yaw/throttle configuration. + // Value is one of JoystickAxis::JOYSTICK_INPUT_MAPPING. + int rollAxis; + int pitchAxis; int yawAxis; - int autoButtonMapping; - int manualButtonMapping; - int stabilizeButtonMapping; - SDL_Event event; + int throttleAxis; + + // Cache information on the joystick instead of polling the SDL everytime. + int numJoysticks; ///< Total number of joysticks detected by the SDL. QString joystickName; + int joystickID; + int joystickNumAxes; + int joystickNumButtons; + + // Track axis/button settings based on a Joystick/AutopilotType/SystemType triplet. + // This is only a double-map, because settings are stored/loaded based on joystick + // name first, so only the settings for the current joystick need to be stored at any given time. + // Pointers are kept to the various settings field to reduce lookup times. + // Note that the mapping (0,0) corresponds to when no UAS is connected. Since this corresponds + // to a generic vehicle type and a generic autopilot, this is a pretty safe default. + QMap > joystickSettings; + + // Track the last state of the axes, buttons, and hats for only emitting change signals. + QList joystickAxes; ///< The values of every axes during the last sample. + quint16 joystickButtons; ///< The state of every button. Bitfield supporting 16 buttons with 1s indicating that the button is down. + int xHat, yHat; ///< The horizontal/vertical hat directions. Values are -1, 0, 1, with (-1,-1) indicating bottom-left. + /** + * @brief Called before main run() event loop starts. Waits for joysticks to be connected. + */ void init(); signals: @@ -135,49 +217,40 @@ signals: /** * @brief Signal containing all joystick raw positions * - * @param roll forward / pitch / x axis, front: 1, center: 0, back: -1 - * @param pitch left / roll / y axis, left: -1, middle: 0, right: 1 - * @param yaw turn axis, left-turn: -1, centered: 0, right-turn: 1 - * @param thrust Thrust, 0%: 0, 100%: 1 + * @param roll forward / pitch / x axis, front: 1, center: 0, back: -1. If the roll axis isn't defined, NaN is transmit instead. + * @param pitch left / roll / y axis, left: -1, middle: 0, right: 1. If the roll axis isn't defined, NaN is transmit instead. + * @param yaw turn axis, left-turn: -1, centered: 0, right-turn: 1. If the roll axis isn't defined, NaN is transmit instead. + * @param throttle Throttle, -100%:-1.0, 0%: 0.0, 100%: 1.0. If the roll axis isn't defined, NaN is transmit instead. * @param xHat hat vector in forward-backward direction, +1 forward, 0 center, -1 backward * @param yHat hat vector in left-right direction, -1 left, 0 center, +1 right */ - void joystickChanged(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons); - - /** - * @brief Thrust lever of the joystick has changed - * - * @param thrust Thrust, 0%: 0, 100%: 1.0 - */ - void thrustChanged(int thrust); + void joystickChanged(double roll, double pitch, double yaw, double throttle, int xHat, int yHat, int buttons); /** - * @brief X-Axis / forward-backward axis has changed + * @brief Emit a new value for an axis * - * @param x forward / pitch / x axis, front: +1.0, center: 0.0, back: -1.0 + * @param value Value of the axis, between -1.0 and 1.0. */ - void xChanged(int x); + void axisValueChanged(int axis, float value); /** - * @brief Y-Axis / left-right axis has changed - * - * @param y left / roll / y axis, left: -1.0, middle: 0.0, right: +1.0 + * @brief Joystick button has changed state from unpressed to pressed. + * @param key index of the pressed key */ - void yChanged(int y); + void buttonPressed(int key); /** - * @brief Yaw / left-right turn has changed + * @brief Joystick button has changed state from pressed to unpressed. * - * @param yaw turn axis, left-turn: -1.0, middle: 0.0, right-turn: +1.0 + * @param key index of the released key */ - void yawChanged(int yaw); + void buttonReleased(int key); /** - * @brief Joystick button has been pressed - * - * @param key index of the pressed key + * @brief A joystick button was pressed that had a corresponding action. + * @param action The index of the action to trigger. Dependent on UAS. */ - void buttonPressed(int key); + void actionTriggered(int action); /** * @brief Hat (8-way switch on the top) has changed position @@ -196,42 +269,51 @@ signals: */ void hatDirectionChanged(int x, int y); -public slots: - void setActiveUAS(UASInterface* uas); - void setMappingThrustAxis(int mapping) - { - thrustAxis = mapping; - } - - void setMappingXAxis(int mapping) - { - xAxis = mapping; - } - - void setMappingYAxis(int mapping) - { - yAxis = mapping; - } - - void setMappingYawAxis(int mapping) - { - yawAxis = mapping; - } + /** @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*); - void setMappingAutoButton(int mapping) - { - autoButtonMapping = mapping; - } + /** @brief Signals that new joystick-specific settings were changed. Useful for triggering updates that at dependent on the current joystick. */ + void joystickSettingsChanged(); - void setMappingManualButton(int mapping) - { - manualButtonMapping = mapping; - } + /** @brief The JoystickInput has switched to a different joystick. UI should be adjusted accordingly. */ + void newJoystickSelected(); - void setMappingStabilizeButton(int mapping) - { - stabilizeButtonMapping = mapping; - } +public slots: + /** @brief Enable or disable emitting the high-level control signals from the joystick. */ + void setEnabled(bool enable); + /** @brief Specify the UAS that this input should forward joystickChanged signals and buttonPresses to. */ + void setActiveUAS(UASInterface* uas); + /** @brief Switch to a new joystick by ID number. Both buttons and axes are updated with the proper signals emitted. */ + void setActiveJoystick(int id); + /** + * @brief Change the control mapping for a given joystick axis. + * @param axisID The axis to modify (0-indexed) + * @param newMapping The mapping to use. + * @see JOYSTICK_INPUT_MAPPING + */ + void setAxisMapping(int axis, JoystickInput::JOYSTICK_INPUT_MAPPING newMapping); + /** + * @brief Specify if an axis should be inverted. + * @param axis The ID of the axis. + * @param inverted True indicates inverted from normal. Varies by controller. + */ + void setAxisInversion(int axis, bool inverted); + /** + * @brief Specify that an axis should only transmit the positive values. Useful for controlling throttle from auto-centering axes. + * @param axis Which axis has its range limited. + * @param limitRange If true only the positive half of this axis will be read. + */ + void setAxisRangeLimit(int axis, bool limitRange); + /** + * @brief Specify a button->action mapping for the given uas. + * This mapping is applied based on UAS autopilot type and UAS system type. + * Connects the buttonEmitted signal for the corresponding button to the corresponding action for the current UAS. + * @param button The numeric ID for the button + * @param action The numeric ID of the action for this UAS to map to. + */ + void setButtonAction(int button, int action); }; #endif // _JOYSTICKINPUT_H_ diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 84bc39a70d4baebe3c02dd2ffecd4e5545311ebd..93d58789137a5f78c7c83f09bdfb5068c46d9af7 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -34,9 +34,9 @@ /** * Gets the settings from the previous UAS (name, airframe, autopilot, battery specs) -* by calling readSettings. This means the new UAS will have the same settings +* by calling readSettings. This means the new UAS will have the same settings * as the previous one created unless one calls deleteSettings in the code after -* creating the UAS. +* creating the UAS. */ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), uasId(id), @@ -146,16 +146,74 @@ UAS::UAS(MAVLinkProtocol* protocol, int id) : UASInterface(), componentID[i] = -1; componentMulti[i] = false; } - + + // Store a list of available actions for this UAS. + // Basically everything exposted as a SLOT with no return value or arguments. + + QAction* newAction = new QAction(tr("Arm"), this); + newAction->setToolTip(tr("Enable the UAS so that all actuators are online")); + connect(newAction, SIGNAL(triggered()), this, SLOT(armSystem())); + actions.append(newAction); + + newAction = new QAction(tr("Disarm"), this); + newAction->setToolTip(tr("Disable the UAS so that all actuators are offline")); + connect(newAction, SIGNAL(triggered()), this, SLOT(disarmSystem())); + actions.append(newAction); + + newAction = new QAction(tr("Toggle armed"), this); + newAction->setToolTip(tr("Toggle between armed and disarmed")); + connect(newAction, SIGNAL(triggered()), this, SLOT(toggleAutonomy())); + actions.append(newAction); + + newAction = new QAction(tr("Go home"), this); + newAction->setToolTip(tr("Command the UAS to return to its home position")); + connect(newAction, SIGNAL(triggered()), this, SLOT(home())); + actions.append(newAction); + + newAction = new QAction(tr("Land"), this); + newAction->setToolTip(tr("Command the UAS to land")); + connect(newAction, SIGNAL(triggered()), this, SLOT(land())); + actions.append(newAction); + + newAction = new QAction(tr("Launch"), this); + newAction->setToolTip(tr("Command the UAS to launch itself and begin its mission")); + connect(newAction, SIGNAL(triggered()), this, SLOT(launch())); + actions.append(newAction); + + newAction = new QAction(tr("Resume"), this); + newAction->setToolTip(tr("Command the UAS to continue its mission")); + connect(newAction, SIGNAL(triggered()), this, SLOT(go())); + actions.append(newAction); + + newAction = new QAction(tr("Stop"), this); + newAction->setToolTip(tr("Command the UAS to halt and hold position")); + connect(newAction, SIGNAL(triggered()), this, SLOT(halt())); + actions.append(newAction); + + newAction = new QAction(tr("Go autonomous"), this); + newAction->setToolTip(tr("Set the UAS into an autonomous control mode")); + connect(newAction, SIGNAL(triggered()), this, SLOT(goAutonomous())); + actions.append(newAction); + + newAction = new QAction(tr("Go manual"), this); + newAction->setToolTip(tr("Set the UAS into a manual control mode")); + connect(newAction, SIGNAL(triggered()), this, SLOT(goManual())); + actions.append(newAction); + + newAction = new QAction(tr("Toggle autonomy"), this); + newAction->setToolTip(tr("Toggle between manual and full-autonomy")); + connect(newAction, SIGNAL(triggered()), this, SLOT(toggleAutonomy())); + actions.append(newAction); + color = UASInterface::getNextColor(); setBatterySpecs(QString("9V,9.5V,12.6V")); connect(statusTimeout, SIGNAL(timeout()), this, SLOT(updateState())); connect(this, SIGNAL(systemSpecsChanged(int)), this, SLOT(writeSettings())); statusTimeout->start(500); - readSettings(); + readSettings(); // Initial signals emit disarmed(); - emit armingChanged(false); + emit armingChanged(false); } /** @@ -206,7 +264,7 @@ void UAS::readSettings() /** * Deletes the settings origianally read into the UAS by readSettings. -* This is in case one does not want the old values but would rather +* This is in case one does not want the old values but would rather * start with the values assigned by the constructor. */ void UAS::deleteSettings() @@ -225,6 +283,15 @@ int UAS::getUASID() const return uasId; } +void UAS::triggerAction(int action) +{ + if (action >= 0 && action < actions.size()) + { + qDebug() << "Triggering action: '" << actions[action]->text() << "'"; + actions[action]->trigger(); + } +} + /** * Update the heartbeat. */ @@ -416,15 +483,15 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) emit heartbeat(this); mavlink_heartbeat_t state; mavlink_msg_heartbeat_decode(&message, &state); - - // Send the base_mode and system_status values to the plotter. This uses the ground time - // so the Ground Time checkbox must be ticked for these values to display + + // Send the base_mode and system_status values to the plotter. This uses the ground time + // so the Ground Time checkbox must be ticked for these values to display quint64 time = getUnixTime(); - QString name = QString("M%1:HEARTBEAT.%2").arg(message.sysid); - emit valueChanged(uasId, name.arg("base_mode"), "bits", state.base_mode, time); - emit valueChanged(uasId, name.arg("custom_mode"), "bits", state.custom_mode, time); - emit valueChanged(uasId, name.arg("system_status"), "-", state.system_status, time); - + QString name = QString("M%1:HEARTBEAT.%2").arg(message.sysid); + emit valueChanged(uasId, name.arg("base_mode"), "bits", state.base_mode, time); + emit valueChanged(uasId, name.arg("custom_mode"), "bits", state.custom_mode, time); + emit valueChanged(uasId, name.arg("system_status"), "-", state.system_status, time); + // Set new type if it has changed if (this->type != state.type) { @@ -547,22 +614,22 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) mavlink_sys_status_t state; mavlink_msg_sys_status_decode(&message, &state); - // Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present. + // Prepare for sending data to the realtime plotter, which is every field excluding onboard_control_sensors_present. quint64 time = getUnixTime(); - QString name = QString("M%1:SYS_STATUS.%2").arg(message.sysid); - emit valueChanged(uasId, name.arg("sensors_enabled"), "bits", state.onboard_control_sensors_enabled, time); - emit valueChanged(uasId, name.arg("sensors_health"), "bits", state.onboard_control_sensors_health, time); - emit valueChanged(uasId, name.arg("errors_comm"), "-", state.errors_comm, time); - emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time); - emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time); - emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time); + QString name = QString("M%1:SYS_STATUS.%2").arg(message.sysid); + emit valueChanged(uasId, name.arg("sensors_enabled"), "bits", state.onboard_control_sensors_enabled, time); + emit valueChanged(uasId, name.arg("sensors_health"), "bits", state.onboard_control_sensors_health, time); + emit valueChanged(uasId, name.arg("errors_comm"), "-", state.errors_comm, time); + emit valueChanged(uasId, name.arg("errors_count1"), "-", state.errors_count1, time); + emit valueChanged(uasId, name.arg("errors_count2"), "-", state.errors_count2, time); + emit valueChanged(uasId, name.arg("errors_count3"), "-", state.errors_count3, time); emit valueChanged(uasId, name.arg("errors_count4"), "-", state.errors_count4, time); - // Process CPU load. + // Process CPU load. emit loadChanged(this,state.load/10.0f); - emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time); + emit valueChanged(uasId, name.arg("load"), "%", state.load/10.0f, time); - // Battery charge/time remaining/voltage calculations + // Battery charge/time remaining/voltage calculations currentVoltage = state.voltage_battery/1000.0f; lpVoltage = filterVoltage(currentVoltage); tickLowpassVoltage = tickLowpassVoltage*0.8f + 0.2f*currentVoltage; @@ -596,16 +663,16 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) } emit batteryChanged(this, lpVoltage, currentCurrent, getChargeLevel(), timeRemaining); - emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time); + emit valueChanged(uasId, name.arg("battery_remaining"), "%", getChargeLevel(), time); // emit voltageChanged(message.sysid, currentVoltage); - emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time); + emit valueChanged(uasId, name.arg("battery_voltage"), "V", currentVoltage, time); - // And if the battery current draw is measured, log that also. - if (state.current_battery != -1) - { + // And if the battery current draw is measured, log that also. + if (state.current_battery != -1) + { currentCurrent = ((double)state.current_battery)/100.0f; emit valueChanged(uasId, name.arg("battery_current"), "A", currentCurrent, time); - } + } // LOW BATTERY ALARM if (lpVoltage < warnVoltage && (currentVoltage - 0.2f) < warnVoltage && (currentVoltage > 3.3)) @@ -625,17 +692,17 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) emit positionZControlEnabled(state.onboard_control_sensors_enabled & (1 << 13)); emit positionXYControlEnabled(state.onboard_control_sensors_enabled & (1 << 14)); - // Trigger drop rate updates as needed. Here we convert the incoming - // drop_rate_comm value from 1/100 of a percent in a uint16 to a true - // percentage as a float. We also cap the incoming value at 100% as defined - // by the MAVLink specifications. - if (state.drop_rate_comm > 10000) - { - state.drop_rate_comm = 10000; - } - emit dropRateChanged(this->getUASID(), state.drop_rate_comm/100.0f); - emit valueChanged(uasId, name.arg("drop_rate_comm"), "%", state.drop_rate_comm/100.0f, time); - } + // Trigger drop rate updates as needed. Here we convert the incoming + // drop_rate_comm value from 1/100 of a percent in a uint16 to a true + // percentage as a float. We also cap the incoming value at 100% as defined + // by the MAVLink specifications. + if (state.drop_rate_comm > 10000) + { + state.drop_rate_comm = 10000; + } + emit dropRateChanged(this->getUASID(), state.drop_rate_comm/100.0f); + emit valueChanged(uasId, name.arg("drop_rate_comm"), "%", state.drop_rate_comm/100.0f, time); + } break; case MAVLINK_MSG_ID_ATTITUDE: { @@ -854,13 +921,13 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message) // only accept values in a realistic range // quint64 time = getUnixTime(pos.time_usec); quint64 time = getUnixTime(pos.time_usec); - + emit gpsLocalizationChanged(this, pos.fix_type); // TODO: track localization state not only for gps but also for other loc. sources int loc_type = pos.fix_type; if (loc_type == 1) { - loc_type = 0; + loc_type = 0; } emit localizationChanged(this, loc_type); setSatelliteCount(pos.satellites_visible); @@ -1641,7 +1708,7 @@ void UAS::setLocalOriginAtCurrentGPSPosition() * @param x postion * @param y position * @param z position -*/ +*/ void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw) { #ifdef MAVLINK_ENABLED_PIXHAWK @@ -1661,7 +1728,7 @@ void UAS::setLocalPositionSetpoint(float x, float y, float z, float yaw) * @param x position * @param y position * @param z position -* @param yaw +* @param yaw */ void UAS::setLocalPositionOffset(float x, float y, float z, float yaw) { @@ -1723,8 +1790,8 @@ void UAS::startPressureCalibration() sendMessage(msg); } -/** -* Check if time is smaller than 40 years, assuming no system without Unix +/** +* Check if time is smaller than 40 years, assuming no system without Unix * timestamp runs longer than 40 years continuously without reboot. In worst case * this will add/subtract the communication delay between GCS and MAV, it will * never alter the timestamp in a safety critical way. @@ -1776,11 +1843,11 @@ quint64 UAS::getUnixReferenceTime(quint64 time) /** * @warning If attitudeStamped is enabled, this function will not actually return -* the precise time stamp of this measurement augmented to UNIX time, but will +* the precise time stamp of this measurement augmented to UNIX time, but will * MOVE the timestamp IN TIME to match the last measured attitude. There is no -* reason why one would want this, except for system setups where the onboard +* reason why one would want this, except for system setups where the onboard * clock is not present or broken and datasets should be collected that are still -* roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE +* roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED RUINS THE * SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL! */ quint64 UAS::getUnixTimeFromMs(quint64 time) @@ -1790,10 +1857,10 @@ quint64 UAS::getUnixTimeFromMs(quint64 time) /** * @warning If attitudeStamped is enabled, this function will not actually return -* the precise time stam of this measurement augmented to UNIX time, but will -* MOVE the timestamp IN TIME to match the last measured attitude. There is no -* reason why one would want this, except for system setups where the onboard -* clock is not present or broken and datasets should be collected that are +* the precise time stam of this measurement augmented to UNIX time, but will +* MOVE the timestamp IN TIME to match the last measured attitude. There is no +* reason why one would want this, except for system setups where the onboard +* clock is not present or broken and datasets should be collected that are * still roughly synchronized. PLEASE NOTE THAT ENABLING ATTITUDE STAMPED * RUINS THE SCIENTIFIC NATURE OF THE CORRECT LOGGING FUNCTIONS OF QGROUNDCONTROL! */ @@ -2005,7 +2072,7 @@ QString UAS::getNavModeText(int mode) return QString("UNKNOWN"); } -/** +/** * Get the status of the code and a description of the status. * Status can be unitialized, booting up, calibrating sensors, active * standby, cirtical, emergency, shutdown or unknown. @@ -2176,7 +2243,7 @@ void UAS::readParametersFromStorage() sendMessage(msg); } -/** +/** * @param rate The update rate in Hz the message should be sent */ void UAS::enableAllDataTransmission(int rate) @@ -2204,7 +2271,7 @@ void UAS::enableAllDataTransmission(int rate) sendMessage(msg); } -/** +/** * @param rate The update rate in Hz the message should be sent */ void UAS::enableRawSensorDataTransmission(int rate) @@ -2228,7 +2295,7 @@ void UAS::enableRawSensorDataTransmission(int rate) sendMessage(msg); } -/** +/** * @param rate The update rate in Hz the message should be sent */ void UAS::enableExtendedSystemStatusTransmission(int rate) @@ -2252,7 +2319,7 @@ void UAS::enableExtendedSystemStatusTransmission(int rate) sendMessage(msg); } -/** +/** * @param rate The update rate in Hz the message should be sent */ void UAS::enableRCChannelDataTransmission(int rate) @@ -2281,7 +2348,7 @@ void UAS::enableRCChannelDataTransmission(int rate) #endif } -/** +/** * @param rate The update rate in Hz the message should be sent */ void UAS::enableRawControllerDataTransmission(int rate) @@ -2327,7 +2394,7 @@ void UAS::enableRawControllerDataTransmission(int rate) // sendMessage(msg); //} -/** +/** * @param rate The update rate in Hz the message should be sent */ void UAS::enablePositionTransmission(int rate) @@ -2351,7 +2418,7 @@ void UAS::enablePositionTransmission(int rate) sendMessage(msg); } -/** +/** * @param rate The update rate in Hz the message should be sent */ void UAS::enableExtra1Transmission(int rate) @@ -2376,7 +2443,7 @@ void UAS::enableExtra1Transmission(int rate) sendMessage(msg); } -/** +/** * @param rate The update rate in Hz the message should be sent */ void UAS::enableExtra2Transmission(int rate) @@ -2401,7 +2468,7 @@ void UAS::enableExtra2Transmission(int rate) sendMessage(msg); } -/** +/** * @param rate The update rate in Hz the message should be sent */ void UAS::enableExtra3Transmission(int rate) @@ -2430,7 +2497,7 @@ void UAS::enableExtra3Transmission(int rate) * Set a parameter value onboard * * @param component The component to set the parameter - * @param id Name of the parameter + * @param id Name of the parameter */ void UAS::setParameter(const int component, const QString& id, const QVariant& value) { @@ -2518,7 +2585,7 @@ void UAS::setParameter(const int component, const QString& id, const QVariant& v } } -/** +/** * Request parameter, use parameter name to request it. */ void UAS::requestParameter(int component, int id) @@ -2566,7 +2633,7 @@ void UAS::setSystemType(int systemType) if((systemType >= MAV_TYPE_GENERIC) && (systemType < MAV_TYPE_ENUM_END)) { type = systemType; - + // If the airframe is still generic, change it to a close default type if (airframe == 0) { @@ -2675,8 +2742,36 @@ void UAS::disarmSystem() sendMessage(msg); } -/** -* Set the manual control commands. +void UAS::toggleArmedState() +{ + mavlink_message_t msg; + mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode ^ MAV_MODE_FLAG_SAFETY_ARMED, navMode); + sendMessage(msg); +} + +void UAS::goAutonomous() +{ + mavlink_message_t msg; + mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & MAV_MODE_FLAG_AUTO_ENABLED & ~MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, navMode); + sendMessage(msg); +} + +void UAS::goManual() +{ + mavlink_message_t msg; + mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode & ~MAV_MODE_FLAG_AUTO_ENABLED & MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, navMode); + sendMessage(msg); +} + +void UAS::toggleAutonomy() +{ + mavlink_message_t msg; + mavlink_msg_set_mode_pack(mavlink->getSystemId(), mavlink->getComponentId(), &msg, this->getUASID(), mode ^ MAV_MODE_FLAG_AUTO_ENABLED ^ MAV_MODE_FLAG_MANUAL_INPUT_ENABLED, navMode); + sendMessage(msg); +} + +/** +* Set the manual control commands. * This can only be done if the system has manual inputs enabled and is armed. */ void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons) @@ -2736,27 +2831,6 @@ int UAS::getSystemType() return this->type; } -/** -* @param buttonIndex -*/ -void UAS::receiveButton(int buttonIndex) -{ - switch (buttonIndex) - { - case 0: - - break; - case 1: - - break; - default: - - break; - } - // qDebug() << __FILE__ << __LINE__ << ": Received button clicked signal (button # is: " << buttonIndex << "), UNIMPLEMENTED IN MAVLINK!"; - -} - /** * Halt the uas. */ @@ -2777,8 +2851,8 @@ void UAS::go() sendMessage(msg); } -/** -* Order the robot to return home +/** +* Order the robot to return home */ void UAS::home() { @@ -2794,7 +2868,7 @@ void UAS::home() } /** -* Order the robot to land on the runway +* Order the robot to land on the runway */ void UAS::land() { @@ -3192,8 +3266,8 @@ const QString& UAS::getShortState() const return shortStateText; } -/** -* The mode can be autonomous, guided, manual or armed. It will also return if +/** +* The mode can be autonomous, guided, manual or armed. It will also return if * hardware in the loop is being used. * @return the audio mode text for the id given. */ @@ -3246,7 +3320,7 @@ QString UAS::getAudioModeTextFor(int id) } /** -* The mode returned can be auto, stabilized, test, manual, preflight or unknown. +* The mode returned can be auto, stabilized, test, manual, preflight or unknown. * @return the short text of the mode for the id given. */ QString UAS::getShortModeTextFor(int id) diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 9823351f2017b0c6a7e66299bb5d7c0ad2dabb65..7bc14495044ab5da906add8a2ff806bc018062b4 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -528,6 +528,40 @@ public: paramManager = manager; } int getSystemType(); + + /** + * @brief Returns true for systems that can reverse. If the system has no control over position, it returns false as + * @return If the specified vehicle type can + */ + bool systemCanReverse() const + { + switch(type) + { + case MAV_TYPE_GENERIC: + case MAV_TYPE_FIXED_WING: + case MAV_TYPE_ROCKET: + case MAV_TYPE_FLAPPING_WING: + + // System types that don't have movement + case MAV_TYPE_ANTENNA_TRACKER: + case MAV_TYPE_GCS: + case MAV_TYPE_FREE_BALLOON: + default: + return false; + case MAV_TYPE_QUADROTOR: + case MAV_TYPE_COAXIAL: + case MAV_TYPE_HELICOPTER: + case MAV_TYPE_AIRSHIP: + case MAV_TYPE_GROUND_ROVER: + case MAV_TYPE_SURFACE_BOAT: + case MAV_TYPE_SUBMARINE: + case MAV_TYPE_HEXAROTOR: + case MAV_TYPE_OCTOROTOR: + case MAV_TYPE_TRICOPTER: + return true; + } + } + QString getSystemTypeName() { switch(type) @@ -642,6 +676,11 @@ public: break; } } + /** From UASInterface */ + QList getActions() const + { + return actions; + } public slots: /** @brief Set the autopilot type */ @@ -660,7 +699,7 @@ public slots: this->airframe = airframe; emit systemSpecsChanged(uasId); } - + } /** @brief Set a new name **/ void setUASName(const QString& name); @@ -747,11 +786,23 @@ public slots: void armSystem(); /** @brief Disable the motors */ void disarmSystem(); + /** @brief Toggle the armed state of the system. */ + void toggleArmedState(); + /** + * @brief Tell the UAS to switch into a completely-autonomous mode, so disable manual input. + */ + void goAutonomous(); + /** + * @brief Tell the UAS to switch to manual control. Stabilized attitude may simultaneously be engaged. + */ + void goManual(); + /** + * @brief Tell the UAS to switch between manual and autonomous control. + */ + void toggleAutonomy(); /** @brief Set the values for the manual control of the vehicle */ void setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons); - /** @brief Receive a button pressed event from an input device, e.g. joystick */ - void receiveButton(int buttonIndex); /** @brief Set the values for the 6dof manual control of the vehicle */ void setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw); @@ -836,6 +887,9 @@ public slots: void startDataRecording(); void stopDataRecording(); void deleteSettings(); + + /** @brief Triggers the action associated with the given ID. */ + void triggerAction(int action); signals: /** @brief The main/battery voltage has changed/was updated */ //void voltageChanged(int uasId, double voltage); // Defined in UASInterface already @@ -892,6 +946,7 @@ protected: bool sensorHil; ///< True if sensor HIL is enabled quint64 lastSendTimeGPS; ///< Last HIL GPS message sent quint64 lastSendTimeSensors; + QList actions; ///< A list of actions that this UAS can perform. protected slots: /** @brief Write settings to disk */ diff --git a/src/uas/UASInterface.h b/src/uas/UASInterface.h index 667c02276a8c1f1925489ad70100e229e6faa0f8..127a51fb135f78b00334f8efb3ceccb7456b4629 100644 --- a/src/uas/UASInterface.h +++ b/src/uas/UASInterface.h @@ -242,6 +242,11 @@ public: /** @brief Get the type of the system (airplane, quadrotor, helicopter,..)*/ virtual int getSystemType() = 0; + /** @brief Indicates whether this system is capable of controlling a reverse velocity. + * Used for, among other things, altering joystick input to either -1:1 or 0:1 range. + */ + virtual bool systemCanReverse() const = 0; + virtual QString getSystemTypeName() = 0; /** @brief Get the type of the autopilot (PIXHAWK, APM, UDB, PPZ,..) */ virtual int getAutopilotType() = 0; @@ -255,6 +260,13 @@ public: return color; } + /** @brief Returns a list of actions/commands that this vehicle can perform. + * Used for creating UI elements for built-in functionality for this vehicle. + * Actions should be mappings to `void f(void);` functions that simply issue + * a command to the vehicle. + */ + virtual QList getActions() const = 0; + public slots: /** @brief Set a new name for the system */ diff --git a/src/ui/JoystickAxis.cc b/src/ui/JoystickAxis.cc new file mode 100644 index 0000000000000000000000000000000000000000..5effd6971b6c8cb4481bbebf8d97fb93752a15ed --- /dev/null +++ b/src/ui/JoystickAxis.cc @@ -0,0 +1,92 @@ +#include "JoystickAxis.h" +#include "JoystickInput.h" +#include "ui_JoystickAxis.h" +#include "UASManager.h" +#include + +JoystickAxis::JoystickAxis(int id, QWidget *parent) : + QWidget(parent), + id(id), + ui(new Ui::JoystickAxis) +{ + ui->setupUi(this); + mappingComboBoxChanged(JoystickInput::JOYSTICK_INPUT_MAPPING_NONE); + ui->label->setText(QString::number(id)); + connect(ui->comboBox, SIGNAL(currentIndexChanged(int)), this, SLOT(mappingComboBoxChanged(int))); + connect(ui->invertedCheckBox, SIGNAL(clicked(bool)), this, SLOT(inversionCheckBoxChanged(bool))); + connect(ui->rangeCheckBox, SIGNAL(clicked(bool)), this, SLOT(rangeCheckBoxChanged(bool))); +} + +JoystickAxis::~JoystickAxis() +{ + delete ui; +} + +void JoystickAxis::setValue(float value) +{ + ui->progressBar->setValue(100.0f * value); +} + +void JoystickAxis::setMapping(JoystickInput::JOYSTICK_INPUT_MAPPING newMapping) +{ + ui->comboBox->setCurrentIndex(newMapping); + if (newMapping == JoystickInput::JOYSTICK_INPUT_MAPPING_THROTTLE) + { + ui->rangeCheckBox->show(); + } + else + { + ui->rangeCheckBox->hide(); + } + this->setActiveUAS(UASManager::instance()->getActiveUAS()); +} + +void JoystickAxis::setInverted(bool newValue) +{ + ui->invertedCheckBox->setChecked(newValue); +} + +void JoystickAxis::setRangeLimit(bool newValue) +{ + ui->rangeCheckBox->setChecked(newValue); +} + +void JoystickAxis::mappingComboBoxChanged(int newMapping) +{ + JoystickInput::JOYSTICK_INPUT_MAPPING mapping = (JoystickInput::JOYSTICK_INPUT_MAPPING)newMapping; + emit mappingChanged(id, mapping); + updateUIBasedOnUAS(UASManager::instance()->getActiveUAS(), mapping); +} + +void JoystickAxis::inversionCheckBoxChanged(bool inverted) +{ + emit inversionChanged(id, inverted); +} + +void JoystickAxis::rangeCheckBoxChanged(bool limited) +{ + emit rangeChanged(id, 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 + // 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(); + } + else + { + ui->progressBar->setRange(-100, 100); + ui->rangeCheckBox->hide(); + } +} diff --git a/src/ui/JoystickAxis.h b/src/ui/JoystickAxis.h new file mode 100644 index 0000000000000000000000000000000000000000..6bb94b349a76b96a2b20c6eac0b35433d46d4155 --- /dev/null +++ b/src/ui/JoystickAxis.h @@ -0,0 +1,84 @@ +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + +======================================================================*/ + +/** + * @file + * This class defines a UI element to represent a single controller axis. + * It is used by the JoystickWidget to simplify some of the logic in that class. + */ + +#ifndef JOYSTICKAXIS_H +#define JOYSTICKAXIS_H + +#include +#include "JoystickInput.h" + +namespace Ui { +class JoystickAxis; +} + +class JoystickAxis : public QWidget +{ + Q_OBJECT + +public: + explicit JoystickAxis(int id, QWidget *parent = 0); + ~JoystickAxis(); + void setMapping(JoystickInput::JOYSTICK_INPUT_MAPPING newMapping); + void setInverted(bool newValue); + void setRangeLimit(bool newValue); + +signals: + /** @brief Signal a change in this axis' yaw/pitch/roll mapping */ + void mappingChanged(int id, JoystickInput::JOYSTICK_INPUT_MAPPING newMapping); + /** @brief Signal a change in this axis' inversion status */ + void inversionChanged(int id, bool inversion); + /** @brief Signal a change in this axis' range setting. If limited is true then only the positive values should be read from this axis. */ + void rangeChanged(int id, bool limited); + +public slots: + /** @brief Update the displayed value of the included progressbar. + * @param value A value between -1.0 and 1.0. + */ + void setValue(float value); + /** @brief Specify the UAS that this axis should track for displaying throttle properly. */ + void setActiveUAS(UASInterface* uas); + +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. */ + void mappingComboBoxChanged(int newMapping); + /** @brief Emit signal when the inversion checkbox is changed. */ + void inversionCheckBoxChanged(bool inverted); + /** @brief Emit signal when the range checkbox is changed. */ + void rangeCheckBoxChanged(bool inverted); +}; + +#endif // JOYSTICKAXIS_H diff --git a/src/ui/JoystickAxis.ui b/src/ui/JoystickAxis.ui new file mode 100644 index 0000000000000000000000000000000000000000..212133c5033baf8c50e045f6c407bf56c42f432d --- /dev/null +++ b/src/ui/JoystickAxis.ui @@ -0,0 +1,168 @@ + + + JoystickAxis + + + + 0 + 0 + 80 + 200 + + + + + 0 + 0 + + + + + 40 + 200 + + + + Form + + + + QLayout::SetMinimumSize + + + 1 + + + 2 + + + 1 + + + 2 + + + + + + + + Qt::AlignCenter + + + + + + + + 0 + 0 + + + + Specify what property of the UAS this axis should command + + + + -- + + + + + Yaw + + + + + Pitch + + + + + Roll + + + + + Throttle + + + + + + + + Half range + + + + + + + true + + + + 0 + 0 + + + + + 0 + 100 + + + + Only use the positive values from this axis for control + + + -100 + + + 0 + + + Qt::AlignCenter + + + true + + + Qt::Vertical + + + QProgressBar::TopToBottom + + + %v + + + + + + + + 0 + 0 + + + + + 0 + 25 + + + + Reverse the values for this axis + + + Inverted + + + + + + + + diff --git a/src/ui/JoystickButton.cc b/src/ui/JoystickButton.cc new file mode 100644 index 0000000000000000000000000000000000000000..97941557ba0678bd8bea4c5aee891c491ee3a1c1 --- /dev/null +++ b/src/ui/JoystickButton.cc @@ -0,0 +1,58 @@ +#include "JoystickButton.h" +#include "ui_JoystickButton.h" +#include "UASManager.h" + +JoystickButton::JoystickButton(int id, QWidget *parent) : + QWidget(parent), + id(id), + m_ui(new Ui::JoystickButton) +{ + m_ui->setupUi(this); + m_ui->joystickButtonLabel->setText(QString::number(id)); + this->setActiveUAS(UASManager::instance()->getActiveUAS()); + connect(m_ui->joystickAction, SIGNAL(currentIndexChanged(int)), this, SLOT(actionComboBoxChanged(int))); +} + +JoystickButton::~JoystickButton() +{ + delete m_ui; +} + +void JoystickButton::setActiveUAS(UASInterface* uas) +{ + // Disable signals so that changes to joystickAction don't trigger JoystickInput updates. + disconnect(m_ui->joystickAction, SIGNAL(currentIndexChanged(int)), this, SLOT(actionComboBoxChanged(int))); + if (uas) + { + m_ui->joystickAction->setEnabled(true); + m_ui->joystickAction->clear(); + m_ui->joystickAction->addItem("--"); + QList actions = uas->getActions(); + foreach (QAction* a, actions) + { + 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); + } + 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. + 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); + connect(m_ui->joystickAction, SIGNAL(currentIndexChanged(int)), this, SLOT(actionComboBoxChanged(int))); +} + +void JoystickButton::actionComboBoxChanged(int index) +{ + // Subtract one because the default no-action takes the 0-spot. + emit actionChanged(id, index - 1); +} diff --git a/src/ui/JoystickButton.h b/src/ui/JoystickButton.h new file mode 100644 index 0000000000000000000000000000000000000000..559f49201891615b996bdad4af0fa8939735b680 --- /dev/null +++ b/src/ui/JoystickButton.h @@ -0,0 +1,66 @@ +/*===================================================================== + +QGroundControl Open Source Ground Control Station + +This file is part of the QGROUNDCONTROL project + + QGROUNDCONTROL is free software: you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation, either version 3 of the License, or + (at your option) any later version. + + QGROUNDCONTROL is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with QGROUNDCONTROL. If not, see . + +======================================================================*/ + +/** + * @file + * This class defines a UI element to represent a single controller axis. + * It is used by the JoystickWidget to simplify some of the logic in that class. + */ + +#ifndef JOYSTICKBUTTON_H +#define JOYSTICKBUTTON_H + +#include + +#include "UASInterface.h" + +namespace Ui +{ +class JoystickButton; +} + +class JoystickButton : public QWidget +{ + Q_OBJECT + +public: + explicit JoystickButton(int id, QWidget *parent = 0); + virtual ~JoystickButton(); + +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. + * Values 0 and higher indicate a specific action, while -1 indicates no action. */ + void setAction(int index); + +signals: + /** @brief Signal a change in this buttons' action mapping */ + void actionChanged(int id, int index); + +private: + int id; + Ui::JoystickButton *m_ui; + +private slots: + void actionComboBoxChanged(int index); +}; +#endif // JOYSTICKBUTTON_H diff --git a/src/ui/JoystickButton.ui b/src/ui/JoystickButton.ui new file mode 100644 index 0000000000000000000000000000000000000000..1598d22273c2a4929d4d60c896fd37624158ca4c --- /dev/null +++ b/src/ui/JoystickButton.ui @@ -0,0 +1,92 @@ + + + JoystickButton + + + + 0 + 0 + 125 + 29 + + + + + 0 + 0 + + + + + 50 + 0 + + + + Form + + + + QLayout::SetMinimumSize + + + 2 + + + 1 + + + 2 + + + 1 + + + + + + 0 + 0 + + + + + 20 + 0 + + + + + + + Qt::AlignCenter + + + + + + + false + + + + 0 + 0 + + + + + 60 + 0 + + + + QComboBox::AdjustToContents + + + + + + + + diff --git a/src/ui/JoystickWidget.cc b/src/ui/JoystickWidget.cc index 1fb49e249e11a975507c7bd8fedf082f9df239c2..5b5150791f8d437107d26177ffeafcb0cce8804c 100644 --- a/src/ui/JoystickWidget.cc +++ b/src/ui/JoystickWidget.cc @@ -1,10 +1,14 @@ #include "JoystickWidget.h" +#include "MainWindow.h" #include "ui_JoystickWidget.h" -#include +#include "JoystickButton.h" +#include "JoystickAxis.h" + #include JoystickWidget::JoystickWidget(JoystickInput* joystick, QWidget *parent) : QDialog(parent), + joystick(joystick), m_ui(new Ui::JoystickWidget) { m_ui->setupUi(this); @@ -14,42 +18,84 @@ JoystickWidget::JoystickWidget(JoystickInput* joystick, QWidget *parent) : position.moveCenter(QDesktopWidget().availableGeometry().center()); move(position.topLeft()); - clearKeys(); - this->joystick = joystick; + // Initialize the UI based on the current joystick + initUI(); + + // Watch for button, axis, and hat input events from the joystick. + connect(this->joystick, SIGNAL(buttonPressed(int)), this, SLOT(joystickButtonPressed(int))); + connect(this->joystick, SIGNAL(buttonReleased(int)), this, SLOT(joystickButtonReleased(int))); + connect(this->joystick, SIGNAL(axisValueChanged(int,float)), this, SLOT(updateAxisValue(int,float))); + connect(this->joystick, SIGNAL(hatDirectionChanged(int,int)), this, SLOT(setHat(int,int))); + + // 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())); - m_ui->rollMapSpinBox->setValue(joystick->getMappingXAxis()); - m_ui->pitchMapSpinBox->setValue(joystick->getMappingYAxis()); - m_ui->yawMapSpinBox->setValue(joystick->getMappingYawAxis()); - m_ui->throttleMapSpinBox->setValue(joystick->getMappingThrustAxis()); - m_ui->autoMapSpinBox->setValue(joystick->getMappingAutoButton()); + // If the selected joystick is changed, update the JoystickInput. + connect(m_ui->joystickNameComboBox, SIGNAL(currentIndexChanged(int)), this->joystick, SLOT(setActiveJoystick(int))); + // Also wait for the JoystickInput to switch, then update our UI. + connect(this->joystick, SIGNAL(newJoystickSelected()), this, SLOT(createUIForJoystick())); - connect(this->joystick, SIGNAL(joystickChanged(double,double,double,double,int,int,int)), this, SLOT(updateJoystick(double,double,double,double,int,int))); - connect(this->joystick, SIGNAL(buttonPressed(int)), this, SLOT(pressKey(int))); - connect(m_ui->rollMapSpinBox, SIGNAL(valueChanged(int)), this->joystick, SLOT(setMappingXAxis(int))); - connect(m_ui->pitchMapSpinBox, SIGNAL(valueChanged(int)), this->joystick, SLOT(setMappingYAxis(int))); - connect(m_ui->yawMapSpinBox, SIGNAL(valueChanged(int)), this->joystick, SLOT(setMappingYawAxis(int))); - connect(m_ui->throttleMapSpinBox, SIGNAL(valueChanged(int)), this->joystick, SLOT(setMappingThrustAxis(int))); - connect(m_ui->autoMapSpinBox, SIGNAL(valueChanged(int)), this->joystick, SLOT(setMappingAutoButton(int))); + // Initialize the UI to the current JoystickInput state. Also make sure to listen for future changes + // so that the UI can be updated. + connect(m_ui->enableCheckBox, SIGNAL(toggled(bool)), m_ui->joystickFrame, SLOT(setEnabled(bool))); + m_ui->enableCheckBox->setChecked(this->joystick->enabled()); // Needs to be after connecting to the joystick frame and before watching for enabled events from JoystickInput. + connect(m_ui->enableCheckBox, SIGNAL(toggled(bool)), this->joystick, SLOT(setEnabled(bool))); - // Display the widget - this->window()->setWindowTitle(tr("Joystick Settings")); - if (joystick) updateStatus(tr("Found joystick: %1").arg(joystick->getName())); + // Update the button label colors based on the current theme and watch for future theme changes. + styleChanged(MainWindow::instance()->getStyle()); + connect(MainWindow::instance(), SIGNAL(styleChanged(MainWindow::QGC_MAINWINDOW_STYLE)), this, SLOT(styleChanged(MainWindow::QGC_MAINWINDOW_STYLE))); + // Display the widget above all other windows. + this->raise(); this->show(); } -JoystickWidget::~JoystickWidget() +void JoystickWidget::initUI() { - delete m_ui; + // Add the joysticks to the top combobox. They're indexed by their item number. + // And set the currently-selected combobox item to the current joystick. + int joysticks = joystick->getNumJoysticks(); + if (joysticks) + { + for (int i = 0; i < joysticks; i++) + { + m_ui->joystickNameComboBox->addItem(joystick->getJoystickNameById(i)); + } + m_ui->joystickNameComboBox->setCurrentIndex(joystick->getJoystickID()); + // And if joystick support is enabled, show the UI. + if (m_ui->enableCheckBox->isChecked()) + { + m_ui->joystickFrame->setEnabled(true); + } + + // Create the initial UI. + createUIForJoystick(); + } + // But if there're no joysticks, disable everything and hide empty UI. + else + { + m_ui->enableCheckBox->setEnabled(false); + m_ui->joystickNameComboBox->addItem(tr("No joysticks found. Connect and restart QGC to add one.")); + m_ui->joystickNameComboBox->setEnabled(false); + m_ui->joystickFrame->hide(); + } +} + +void JoystickWidget::styleChanged(MainWindow::QGC_MAINWINDOW_STYLE newStyle) +{ + if (newStyle == MainWindow::QGC_MAINWINDOW_STYLE_LIGHT) + { + buttonLabelColor = QColor(0x73, 0xD9, 0x5D); + } + else + { + buttonLabelColor = QColor(0x14, 0xC6, 0x14); + } } -void JoystickWidget::updateJoystick(double roll, double pitch, double yaw, double thrust, int xHat, int yHat) +JoystickWidget::~JoystickWidget() { - setX(roll); - setY(pitch); - setZ(yaw); - setThrottle(thrust); - setHat(xHat, yHat); + delete m_ui; } void JoystickWidget::changeEvent(QEvent *e) @@ -63,98 +109,147 @@ void JoystickWidget::changeEvent(QEvent *e) } } - -void JoystickWidget::setThrottle(float thrust) +void JoystickWidget::updateUI() { - m_ui->thrust->setValue(thrust*100); -} + // 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); + } -void JoystickWidget::setX(float x) -{ - m_ui->xSlider->setValue(x*100); - m_ui->xValue->display(x*100); + // Update the axis mappings + int rollAxis = joystick->getMappingRollAxis(); + int pitchAxis = joystick->getMappingPitchAxis(); + int yawAxis = joystick->getMappingYawAxis(); + int throttleAxis = joystick->getMappingThrottleAxis(); + for (int i = 0; i < axes.size(); i++) + { + JoystickAxis* axis = axes[i]; + JoystickInput::JOYSTICK_INPUT_MAPPING mapping = JoystickInput::JOYSTICK_INPUT_MAPPING_NONE; + if (i == rollAxis) + { + mapping = JoystickInput::JOYSTICK_INPUT_MAPPING_ROLL; + } + else if (i == pitchAxis) + { + mapping = JoystickInput::JOYSTICK_INPUT_MAPPING_PITCH; + } + else if (i == yawAxis) + { + mapping = JoystickInput::JOYSTICK_INPUT_MAPPING_YAW; + } + else if (i == throttleAxis) + { + mapping = JoystickInput::JOYSTICK_INPUT_MAPPING_THROTTLE; + } + axis->setMapping(mapping); + bool inverted = joystick->getInvertedForAxis(i); + axis->setInverted(inverted); + bool limited = joystick->getRangeLimitForAxis(i); + axis->setRangeLimit(limited); + } } -void JoystickWidget::setY(float y) +void JoystickWidget::createUIForJoystick() { - m_ui->ySlider->setValue(y*100); - m_ui->yValue->display(y*100); -} + // Delete all the old UI elements + foreach (JoystickButton* b, buttons) + { + delete b; + } + buttons.clear(); + foreach (JoystickAxis* a, axes) + { + delete a; + } + axes.clear(); + + // And add the necessary button displays for this joystick. + int newButtons = joystick->getJoystickNumButtons(); + if (newButtons) + { + m_ui->buttonBox->show(); + for (int i = 0; i < newButtons; i++) + { + 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(this->joystick, SIGNAL(activeUASSet(UASInterface*)), button, SLOT(setActiveUAS(UASInterface*))); + m_ui->buttonLayout->addWidget(button); + buttons.append(button); + } + } + else + { + m_ui->buttonBox->hide(); + } -void JoystickWidget::setZ(float z) -{ - m_ui->dial->setValue(z*100); + // Do the same for the axes supported by this joystick. + int rollAxis = joystick->getMappingRollAxis(); + int pitchAxis = joystick->getMappingPitchAxis(); + int yawAxis = joystick->getMappingYawAxis(); + int throttleAxis = joystick->getMappingThrottleAxis(); + int newAxes = joystick->getJoystickNumAxes(); + if (newAxes) + { + for (int i = 0; i < newAxes; i++) + { + JoystickAxis* axis = new JoystickAxis(i, m_ui->axesBox); + axis->setValue(joystick->getCurrentValueForAxis(i)); + if (i == rollAxis) + { + axis->setMapping(JoystickInput::JOYSTICK_INPUT_MAPPING_ROLL); + } + else if (i == pitchAxis) + { + axis->setMapping(JoystickInput::JOYSTICK_INPUT_MAPPING_PITCH); + } + else if (i == yawAxis) + { + axis->setMapping(JoystickInput::JOYSTICK_INPUT_MAPPING_YAW); + } + else if (i == throttleAxis) + { + axis->setMapping(JoystickInput::JOYSTICK_INPUT_MAPPING_THROTTLE); + } + axis->setInverted(joystick->getInvertedForAxis(i)); + axis->setRangeLimit(joystick->getRangeLimitForAxis(i)); + 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(this->joystick, SIGNAL(activeUASSet(UASInterface*)), axis, SLOT(setActiveUAS(UASInterface*))); + m_ui->axesLayout->addWidget(axis); + axes.append(axis); + } + } + else + { + m_ui->axesBox->hide(); + } } -void JoystickWidget::setHat(float x, float y) +void JoystickWidget::updateAxisValue(int axis, float value) { - updateStatus(tr("Hat position: x: %1, y: %2").arg(x).arg(y)); + if (axis < axes.size()) + { + axes.at(axis)->setValue(value); + } } -void JoystickWidget::clearKeys() +void JoystickWidget::setHat(int x, int y) { - QString colorstyle; - QColor buttonStyleColor = QColor(200, 20, 20); - colorstyle = QString("QLabel { border: 1px solid #EEEEEE; border-radius: 4px; padding: 0px; margin: 0px; background-color: %1;}").arg(buttonStyleColor.name()); - - m_ui->button0->setStyleSheet(colorstyle); - m_ui->button1->setStyleSheet(colorstyle); - m_ui->button2->setStyleSheet(colorstyle); - m_ui->button3->setStyleSheet(colorstyle); - m_ui->button4->setStyleSheet(colorstyle); - m_ui->button5->setStyleSheet(colorstyle); - m_ui->button6->setStyleSheet(colorstyle); - m_ui->button7->setStyleSheet(colorstyle); - m_ui->button8->setStyleSheet(colorstyle); - m_ui->button9->setStyleSheet(colorstyle); - m_ui->button10->setStyleSheet(colorstyle); + m_ui->statusLabel->setText(tr("Hat position: x: %1, y: %2").arg(x).arg(y)); } -void JoystickWidget::pressKey(int key) +void JoystickWidget::joystickButtonPressed(int key) { - QString colorstyle; - QColor buttonStyleColor = QColor(20, 200, 20); - colorstyle = QString("QLabel { border: 1px solid #EEEEEE; border-radius: 4px; padding: 0px; margin: 0px; background-color: %1;}").arg(buttonStyleColor.name()); - switch(key) { - case 0: - m_ui->button0->setStyleSheet(colorstyle); - break; - case 1: - m_ui->button1->setStyleSheet(colorstyle); - break; - case 2: - m_ui->button2->setStyleSheet(colorstyle); - break; - case 3: - m_ui->button3->setStyleSheet(colorstyle); - break; - case 4: - m_ui->button4->setStyleSheet(colorstyle); - break; - case 5: - m_ui->button5->setStyleSheet(colorstyle); - break; - case 6: - m_ui->button6->setStyleSheet(colorstyle); - break; - case 7: - m_ui->button7->setStyleSheet(colorstyle); - break; - case 8: - m_ui->button8->setStyleSheet(colorstyle); - break; - case 9: - m_ui->button9->setStyleSheet(colorstyle); - break; - case 10: - m_ui->button10->setStyleSheet(colorstyle); - break; - } - QTimer::singleShot(20, this, SLOT(clearKeys())); - updateStatus(tr("Key %1 pressed").arg(key)); + QString colorStyle = QString("QLabel { background-color: %1;}").arg(buttonLabelColor.name()); + buttons.at(key)->setStyleSheet(colorStyle); } -void JoystickWidget::updateStatus(const QString& status) +void JoystickWidget::joystickButtonReleased(int key) { - m_ui->statusLabel->setText(status); + buttons.at(key)->setStyleSheet(""); } diff --git a/src/ui/JoystickWidget.h b/src/ui/JoystickWidget.h index b6c47c628efaf509212a46669706642ed9a8fc85..c1eb1d51a88f9b5ac4937e0bc571c06fabc27bc5 100644 --- a/src/ui/JoystickWidget.h +++ b/src/ui/JoystickWidget.h @@ -23,7 +23,7 @@ This file is part of the PIXHAWK project /** * @file - * @brief Definition of joystick widget + * @brief Definition of joystick widget. Provides a UI for configuring the joystick settings. * @author Lorenz Meier * */ @@ -32,7 +32,12 @@ This file is part of the PIXHAWK project #define JOYSTICKWIDGET_H #include +#include +#include #include "JoystickInput.h" +#include "MainWindow.h" +#include "JoystickAxis.h" +#include "JoystickButton.h" namespace Ui { @@ -48,41 +53,45 @@ public: virtual ~JoystickWidget(); public slots: + /** @brief Update the UI for a new joystick based on SDL ID. */ + void createUIForJoystick(); /** - * @brief Receive raw joystick values - * - * @param roll forward / pitch / x axis, front: 32'767, center: 0, back: -32'768 - * @param pitch left / roll / y axis, left: -32'768, middle: 0, right: 32'767 - * @param yaw turn axis, left-turn: -32'768, centered: 0, right-turn: 32'767 - * @param thrust Thrust, 0%: 0, 100%: 65535 - * @param xHat hat vector in forward-backward direction, +1 forward, 0 center, -1 backward - * @param yHat hat vector in left-right direction, -1 left, 0 center, +1 right + * @brief Update a given axis with a new value + * @param axis The index of the axis to update. + * @param value The new value for the axis, [-1.0:1.0]. + * @see JoystickInput:axisValueChanged */ - void updateJoystick(double roll, double pitch, double yaw, double thrust, int xHat, int yHat); - /** @brief Throttle lever */ - void setThrottle(float thrust); - /** @brief Back/forth movement */ - void setX(float x); - /** @brief Left/right movement */ - void setY(float y); - /** @brief Wrist rotation */ - void setZ(float z); - /** @brief Hat switch position */ - void setHat(float x, float y); - /** @brief Clear keys */ - void clearKeys(); - /** @brief Joystick keys, as labeled on the joystick */ - void pressKey(int key); - /** @brief Update status string */ - void updateStatus(const QString& status); + void updateAxisValue(int axis, float value); + /** @brief Update the UI with new values for the hat. + * @see JoystickInput::hatDirectionChanged + */ + void setHat(int x, int y); + /** @brief Trigger a UI change based on a button being pressed */ + void joystickButtonPressed(int key); + /** @brief Trigger a UI change based on a button being released */ + void joystickButtonReleased(int key); + /** @brief Update the UI color scheme when the MainWindow theme changes. */ + void styleChanged(MainWindow::QGC_MAINWINDOW_STYLE); + /** Update the UI assuming the joystick has stayed the same. */ + void updateUI(); protected: /** @brief UI change event */ virtual void changeEvent(QEvent *e); JoystickInput* joystick; ///< Reference to the joystick + /** @brief a list of all button labels generated for this joystick. */ + QList buttons; + /** @brief a lit of all joystick axes generated for this joystick. */ + QList axes; + /** @brief The color to use for button labels when their corresponding button is pressed */ + QColor buttonLabelColor; private: Ui::JoystickWidget *m_ui; + /** @brief Initialize all dynamic UI elements (button list, joystick names, etc.). + * Only done once at startup. + */ + void initUI(); }; #endif // JOYSTICKWIDGET_H diff --git a/src/ui/JoystickWidget.ui b/src/ui/JoystickWidget.ui index 5c426fc3bc86ee9a0ce3e4844274c5a53137eb6a..f33134eb650d3b93031162cec4b22b819a9a1981 100644 --- a/src/ui/JoystickWidget.ui +++ b/src/ui/JoystickWidget.ui @@ -6,10 +6,16 @@ 0 0 - 497 - 448 + 368 + 274 + + + 0 + 0 + + 368 @@ -17,559 +23,198 @@ - Dialog + Joystick Settings - - + + 8 - + + QLayout::SetFixedSize + + 8 - - - - - 0 - 0 - - - - - 40 - 400 - - - - Buttons - - - Qt::AlignCenter + + 8 + + + 8 + + + 8 + + + + + true - - false + + Enable joysticks - - - 1 - - - 3 - - - - - true - - - - 0 - 0 - - - - 0 - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - 1 - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - 2 - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - 3 - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - 4 - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - 5 - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - 6 - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - 7 - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - 8 - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - 9 - - - Qt::AlignCenter - - - - - - - true - - - - 0 - 0 - - - - 10 - - - Qt::AlignCenter - - - - - - - - Mappings + + + + true - - Qt::AlignCenter + + + 0 + 0 + - - - - - Throttle - - - - - - - Stabilized Button - - - - - - - Auto Button - - - - - - - Manual Button - - - - - - - Pitch Axis - - - - - - - Yaw Axis - - - - - - - Roll Axis - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - Stick + + + + false + + + QFrame::StyledPanel - - Qt::AlignCenter + + QFrame::Sunken - - - 6 + + + QLayout::SetMinimumSize - - - - - 0 - 0 - - - - - 40 - 24 - - - - QFrame::Plain - - - true - - - 3 - - - QLCDNumber::Flat - - - - - - - false - - - -100 - - - 100 - - - Qt::Vertical - - - - - - - true - - - - 40 - 24 - - - - QFrame::Plain - - - true - - - 3 - - - QLCDNumber::Flat - - - - - - - false - - - -100 - - - 100 - - - - - - - Y - - - Qt::AlignRight|Qt::AlignTrailing|Qt::AlignVCenter - - - - - - - false - - - -100 - - - 100 - - - Qt::Horizontal - - + + + + + + + 0 + 0 + + + + + 100 + 0 + + + + + 16777215 + 16777215 + + + + Buttons + + + Qt::AlignCenter + + + false + + + + 1 + + + QLayout::SetMinimumSize + + + 3 + + + 3 + + + 3 + + + 3 + + + + + + + + + 0 + 0 + + + + + 100 + 0 + + + + Axes + + + Qt::AlignCenter + + + + QLayout::SetMinimumSize + + + + + - - + + - X + - - + + + + + 0 + 0 + + + + + 50 + 0 + + - 60 + 16777215 16777215 - - Throttle + + Qt::Horizontal + + + QDialogButtonBox::Ok - - - 0 - - - 2 - - - - - true - - - - 40 - 20 - - - - 0 - - - Qt::Vertical - - - - - - - - - - 1 - - - No joystick detected yet.. waiting - - - - - - - Qt::Horizontal - - - QDialogButtonBox::Cancel|QDialogButtonBox::Ok - - - - - - buttonBox + dialogButtonsBox accepted() JoystickWidget accept() - 248 - 254 + 263 + 438 157 @@ -577,21 +222,5 @@ - - buttonBox - rejected() - JoystickWidget - reject() - - - 316 - 260 - - - 286 - 274 - - - diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 5e3b763255c9d31b2f656026535ad47c76d47ab4..e695f0bbb9590ad42e0b2a3a4d74f7d3a55ea523 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -1512,7 +1512,7 @@ void MainWindow::configure() { joystick->start(); } - joystickWidget = new JoystickWidget(joystick); + joystickWidget = new JoystickWidget(joystick, this); } joystickWidget->show(); } diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index 14c12703dedcf6a7ff49f4b0f7366878c90f45bc..b757d67539a78b1e718fe18b63f045e596a5eb9e 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -51,7 +51,6 @@ This file is part of the QGROUNDCONTROL project #include "MAVLinkSimulationLink.h" #include "ObjectDetectionView.h" #include "submainwindow.h" -#include "JoystickWidget.h" #include "input/JoystickInput.h" #if (defined MOUSE_ENABLED_WIN) | (defined MOUSE_ENABLED_LINUX) #include "Mouse6dofInput.h" @@ -87,6 +86,7 @@ class QSplashScreen; class QGCStatusBar; class Linecharts; class QGCDataPlot2D; +class JoystickWidget; /** * @brief Main Application Window diff --git a/src/ui/MainWindow.ui b/src/ui/MainWindow.ui index 6fb68338334d1740e754943aa103aa8c9f0f4a91..41fb9846a90aa862c4c32983e9beb1619ac81ab3 100644 --- a/src/ui/MainWindow.ui +++ b/src/ui/MainWindow.ui @@ -51,7 +51,7 @@ 0 0 800 - 21 + 25 @@ -200,7 +200,7 @@ :/files/images/devices/input-gaming.svg:/files/images/devices/input-gaming.svg - Joystick Test + Joystick Configuration true diff --git a/src/ui/QGCParamWidget.cc b/src/ui/QGCParamWidget.cc index 068dbebb9d1cdd7c0bf0971e47f23c8ca3722667..4e9700a20cc7650d811cabf8ce8fe4f89bcbf36c 100644 --- a/src/ui/QGCParamWidget.cc +++ b/src/ui/QGCParamWidget.cc @@ -55,7 +55,9 @@ QGCParamWidget::QGCParamWidget(UASInterface* uas, QWidget *parent) : loadSettings(); // Load default values and tooltips - loadParameterInfoCSV(uas->getAutopilotTypeName(), uas->getSystemTypeName()); + QString hey(uas->getAutopilotTypeName()); + QString hey2(uas->getSystemTypeName()); + loadParameterInfoCSV(hey, hey2); // Create tree widget tree = new QTreeWidget(this); diff --git a/src/ui/linechart/ChartPlot.cc b/src/ui/linechart/ChartPlot.cc index 3ec8f922660545d4832b272dca21845d06666182..665ff5233674f633c6cf324359ae4681020c9620 100644 --- a/src/ui/linechart/ChartPlot.cc +++ b/src/ui/linechart/ChartPlot.cc @@ -53,7 +53,7 @@ ChartPlot::ChartPlot(QWidget *parent): } // Now that all objects have been initialized, color everything. - applyColorScheme(MainWindow::instance()->getStyle()); + styleChanged(MainWindow::instance()->getStyle()); } ChartPlot::~ChartPlot() @@ -87,7 +87,7 @@ void ChartPlot::shuffleColors() } } -void ChartPlot::applyColorScheme(MainWindow::QGC_MAINWINDOW_STYLE style) +void ChartPlot::styleChanged(MainWindow::QGC_MAINWINDOW_STYLE style) { // Generate a new color list for curves and recolor them. for (int i = 0; i < numColors; ++i) diff --git a/src/ui/linechart/ChartPlot.h b/src/ui/linechart/ChartPlot.h index fad515190a4a2ad56515b3d31070c853956481a7..74a232039ed2ca9bf9be9c2e09a51cd7d0d13c6c 100644 --- a/src/ui/linechart/ChartPlot.h +++ b/src/ui/linechart/ChartPlot.h @@ -25,7 +25,7 @@ public: public slots: /** @brief Generate coloring for this plot canvas based on current window theme */ - void applyColorScheme(MainWindow::QGC_MAINWINDOW_STYLE style); + void styleChanged(MainWindow::QGC_MAINWINDOW_STYLE style); protected: const static int numColors = 20; diff --git a/src/ui/linechart/LinechartWidget.cc b/src/ui/linechart/LinechartWidget.cc index 2a11f5c296951a8aad91a35838b8e4d046317eaf..e29b655321f24f339aed0d6dfc60ba2a854df252 100644 --- a/src/ui/linechart/LinechartWidget.cc +++ b/src/ui/linechart/LinechartWidget.cc @@ -144,7 +144,7 @@ LinechartWidget::LinechartWidget(int systemid, QWidget *parent) : QWidget(parent // And make sure we're listening for future style changes connect(MainWindow::instance(), SIGNAL(styleChanged(MainWindow::QGC_MAINWINDOW_STYLE)), - this, SLOT(applyColorScheme(MainWindow::QGC_MAINWINDOW_STYLE))); + this, SLOT(styleChanged(MainWindow::QGC_MAINWINDOW_STYLE))); connect(MainWindow::instance(), SIGNAL(styleChanged()), this, SLOT(recolor())); updateTimer->setInterval(updateInterval); @@ -777,7 +777,7 @@ void LinechartWidget::removeCurve(QString curve) void LinechartWidget::recolor() { - activePlot->applyColorScheme(MainWindow::instance()->getStyle()); + activePlot->styleChanged(MainWindow::instance()->getStyle()); foreach (QString key, colorIcons.keys()) { QWidget* colorIcon = colorIcons.value(key, 0); diff --git a/src/ui/uas/UASListWidget.cc b/src/ui/uas/UASListWidget.cc index f0ce7951216cfdac89b924ed655711f64c85183f..d109847dc4140641f1d36b3e39e16d0f67dc4cd7 100644 --- a/src/ui/uas/UASListWidget.cc +++ b/src/ui/uas/UASListWidget.cc @@ -123,7 +123,7 @@ void UASListWidget::updateStatus() { displayString = QString("%1").arg(i.key()->getName()) + displayString; } - qDebug() << p << ": " + displayString; +// qDebug() << p << ": " + displayString; i.value()->setToolTip(displayString); } }