-
-
Notifications
You must be signed in to change notification settings - Fork 4.8k
Joystick improvements #14275
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
base: master
Are you sure you want to change the base?
Joystick improvements #14275
Changes from all commits
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
| Original file line number | Diff line number | Diff line change |
|---|---|---|
|
|
@@ -105,6 +105,7 @@ Joystick::Joystick(const QString &name, int axisCount, int buttonCount, int hatC | |
| ensureFactThread(_joystickSettings.enableManualControlAux4()); | ||
| ensureFactThread(_joystickSettings.enableManualControlAux5()); | ||
| ensureFactThread(_joystickSettings.enableManualControlAux6()); | ||
| ensureFactThread(_joystickSettings.useRcOverrideForAuxChannels()); | ||
| } | ||
|
|
||
| // Changes to manual control extension settings require re-calibration | ||
|
|
@@ -446,6 +447,7 @@ void Joystick::_loadFromSettingsIntoCalibrationData() | |
| qCDebug(JoystickLog) << " enableManualControlAux4:" << _joystickSettings.enableManualControlAux4()->rawValue().toBool(); | ||
| qCDebug(JoystickLog) << " enableManualControlAux5:" << _joystickSettings.enableManualControlAux5()->rawValue().toBool(); | ||
| qCDebug(JoystickLog) << " enableManualControlAux6:" << _joystickSettings.enableManualControlAux6()->rawValue().toBool(); | ||
| qCDebug(JoystickLog) << " useRcOverrideForAuxChannels:" << _joystickSettings.useRcOverrideForAuxChannels()->rawValue().toBool(); | ||
|
|
||
| _loadAxisSettings(calibrated, transmitterMode); | ||
| _loadButtonSettings(); | ||
|
|
@@ -582,6 +584,7 @@ void Joystick::_saveFromCalibrationDataIntoSettings() | |
| qCDebug(JoystickLog) << " enableManualControlAux4:" << _joystickSettings.enableManualControlAux4()->rawValue().toBool(); | ||
| qCDebug(JoystickLog) << " enableManualControlAux5:" << _joystickSettings.enableManualControlAux5()->rawValue().toBool(); | ||
| qCDebug(JoystickLog) << " enableManualControlAux6:" << _joystickSettings.enableManualControlAux6()->rawValue().toBool(); | ||
| qCDebug(JoystickLog) << " useRcOverrideForAuxChannels:" << _joystickSettings.useRcOverrideForAuxChannels()->rawValue().toBool(); | ||
| qCDebug(JoystickLog) << " transmitterMode:" << transmitterMode; | ||
|
|
||
| _clearAxisSettings(); | ||
|
|
@@ -811,7 +814,15 @@ float Joystick::_adjustRange(int value, const AxisCalibration_t &calibration, bo | |
| float axisLength; | ||
| float axisBasis; | ||
|
|
||
| if (value > calibration.center) { | ||
| if (calibration.center == calibration.min) { | ||
| axisBasis = 1.0f; | ||
| valueNormalized = value - calibration.center; | ||
| axisLength = calibration.max - calibration.center; | ||
| } else if (calibration.center == calibration.max) { | ||
| axisBasis = -1.0f; | ||
| valueNormalized = calibration.center - value; | ||
| axisLength = calibration.center - calibration.min; | ||
| } else if (value > calibration.center) { | ||
| axisBasis = 1.0f; | ||
| valueNormalized = value - calibration.center; | ||
| axisLength = calibration.max - calibration.center; | ||
|
|
@@ -821,6 +832,10 @@ float Joystick::_adjustRange(int value, const AxisCalibration_t &calibration, bo | |
| axisLength = calibration.center - calibration.min; | ||
| } | ||
|
|
||
| if (axisLength <= 0.0f) { | ||
| return 0.0f; | ||
| } | ||
|
|
||
| float axisPercent; | ||
| if (withDeadbands) { | ||
| if (valueNormalized > calibration.deadband) { | ||
|
|
@@ -842,6 +857,19 @@ float Joystick::_adjustRange(int value, const AxisCalibration_t &calibration, bo | |
| return std::max(-1.0f, std::min(correctedValue, 1.0f)); | ||
| } | ||
|
|
||
| uint16_t Joystick::_adjustRangeToRcOverridePwm(int value, const AxisCalibration_t &calibration, bool withDeadbands) | ||
| { | ||
| const float normalizedValue = _adjustRange(value, calibration, withDeadbands); | ||
| const bool oneSidedAxis = (calibration.center == calibration.min) || (calibration.center == calibration.max); | ||
|
|
||
| float pwmValue = 1500.0f + (std::clamp(normalizedValue, -1.0f, 1.0f) * 500.0f); | ||
| if (oneSidedAxis) { | ||
| pwmValue = 1000.0f + (std::clamp(normalizedValue, 0.0f, 1.0f) * 1000.0f); | ||
| } | ||
|
|
||
| return static_cast<uint16_t>(std::lround(std::clamp(pwmValue, 1000.0f, 2000.0f))); | ||
| } | ||
|
Comment on lines
+860
to
+871
|
||
|
|
||
| void Joystick::_handleAxis() | ||
| { | ||
| const int axisDelay = static_cast<int>(1000.0 / _joystickSettings.axisFrequencyHz()->rawValue().toDouble()); | ||
|
|
@@ -883,6 +911,7 @@ void Joystick::_handleAxis() | |
| bool negativeThrust = _joystickSettings.negativeThrust()->rawValue().toBool(); | ||
| bool circleCorrection = _joystickSettings.circleCorrection()->rawValue().toBool(); | ||
| bool throttleSmoothing = _joystickSettings.throttleSmoothing()->rawValue().toBool(); | ||
| bool useRcOverrideForAuxChannels = _joystickSettings.useRcOverrideForAuxChannels()->rawValue().toBool(); | ||
| double exponentialPercent = _joystickSettings.exponentialPct()->rawValue().toDouble(); | ||
|
|
||
| if (_getJoystickAxisForAxisFunction(rollFunction) == kJoystickAxisNotAssigned || | ||
|
|
@@ -919,14 +948,22 @@ void Joystick::_handleAxis() | |
| axisIndex = _getJoystickAxisForAxisFunction(rollExtensionFunction); | ||
| rollExtension = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| } | ||
| std::array<uint16_t, 6> auxOverrideValues{}; | ||
| std::array<bool, 6> auxOverrideEnabled{}; | ||
|
|
||
| float aux1 = qQNaN(); | ||
| if (_joystickSettings.enableManualControlAux1()->rawValue().toBool()) { | ||
| if (_getJoystickAxisForAxisFunction(aux1ExtensionFunction) == kJoystickAxisNotAssigned) { | ||
| qCWarning(JoystickLog) << "Internal Error: Missing aux1 extension axis function mapping!"; | ||
| return; | ||
| } | ||
| axisIndex = _getJoystickAxisForAxisFunction(aux1ExtensionFunction); | ||
| aux1 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| if (useRcOverrideForAuxChannels) { | ||
| auxOverrideValues[0] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| auxOverrideEnabled[0] = true; | ||
| } else { | ||
| aux1 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| } | ||
| } | ||
| float aux2 = qQNaN(); | ||
| if (_joystickSettings.enableManualControlAux2()->rawValue().toBool()) { | ||
|
|
@@ -935,7 +972,12 @@ void Joystick::_handleAxis() | |
| return; | ||
| } | ||
| axisIndex = _getJoystickAxisForAxisFunction(aux2ExtensionFunction); | ||
| aux2 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| if (useRcOverrideForAuxChannels) { | ||
| auxOverrideValues[1] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| auxOverrideEnabled[1] = true; | ||
| } else { | ||
| aux2 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| } | ||
| } | ||
| float aux3 = qQNaN(); | ||
| if (_joystickSettings.enableManualControlAux3()->rawValue().toBool()) { | ||
|
|
@@ -944,7 +986,12 @@ void Joystick::_handleAxis() | |
| return; | ||
| } | ||
| axisIndex = _getJoystickAxisForAxisFunction(aux3ExtensionFunction); | ||
| aux3 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| if (useRcOverrideForAuxChannels) { | ||
| auxOverrideValues[2] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| auxOverrideEnabled[2] = true; | ||
| } else { | ||
| aux3 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| } | ||
| } | ||
| float aux4 = qQNaN(); | ||
| if (_joystickSettings.enableManualControlAux4()->rawValue().toBool()) { | ||
|
|
@@ -953,7 +1000,12 @@ void Joystick::_handleAxis() | |
| return; | ||
| } | ||
| axisIndex = _getJoystickAxisForAxisFunction(aux4ExtensionFunction); | ||
| aux4 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| if (useRcOverrideForAuxChannels) { | ||
| auxOverrideValues[3] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| auxOverrideEnabled[3] = true; | ||
| } else { | ||
| aux4 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| } | ||
| } | ||
| float aux5 = qQNaN(); | ||
| if (_joystickSettings.enableManualControlAux5()->rawValue().toBool()) { | ||
|
|
@@ -962,7 +1014,12 @@ void Joystick::_handleAxis() | |
| return; | ||
| } | ||
| axisIndex = _getJoystickAxisForAxisFunction(aux5ExtensionFunction); | ||
| aux5 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| if (useRcOverrideForAuxChannels) { | ||
| auxOverrideValues[4] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| auxOverrideEnabled[4] = true; | ||
| } else { | ||
| aux5 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| } | ||
| } | ||
| float aux6 = qQNaN(); | ||
| if (_joystickSettings.enableManualControlAux6()->rawValue().toBool()) { | ||
|
|
@@ -971,7 +1028,12 @@ void Joystick::_handleAxis() | |
| return; | ||
| } | ||
| axisIndex = _getJoystickAxisForAxisFunction(aux6ExtensionFunction); | ||
| aux6 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| if (useRcOverrideForAuxChannels) { | ||
| auxOverrideValues[5] = _adjustRangeToRcOverridePwm(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| auxOverrideEnabled[5] = true; | ||
| } else { | ||
| aux6 = _adjustRange(_getAxisValue(axisIndex), _rgCalibration[axisIndex], useDeadband); | ||
| } | ||
| } | ||
|
|
||
| if (throttleSmoothing) { | ||
|
|
@@ -1023,7 +1085,8 @@ void Joystick::_handleAxis() | |
| << "aux3:" << aux3 | ||
| << "aux4:" << aux4 | ||
| << "aux5:" << aux5 | ||
| << "aux6:" << aux6; | ||
| << "aux6:" << aux6 | ||
| << "useRcOverrideForAuxChannels:" << useRcOverrideForAuxChannels; | ||
|
|
||
| // NOTE: The buttonPressedBits going to MANUAL_CONTROL are currently used by ArduSub (and it only handles 16 bits) | ||
| // Set up button bitmap | ||
|
|
@@ -1042,6 +1105,7 @@ void Joystick::_handleAxis() | |
|
|
||
|
|
||
| vehicle->sendJoystickDataThreadSafe(roll, pitch, yaw, throttle, lowButtons, highButtons, pitchExtension, rollExtension, aux1, aux2, aux3, aux4, aux5, aux6); | ||
| vehicle->sendJoystickAuxRcOverrideThreadSafe(auxOverrideValues, auxOverrideEnabled, useRcOverrideForAuxChannels); | ||
| } | ||
| } | ||
|
|
||
|
|
@@ -1145,6 +1209,7 @@ void Joystick::_stopPollingForConfiguration() | |
| void Joystick::_stopAllPolling() | ||
| { | ||
| if (_pollingVehicle) { | ||
| _pollingVehicle->sendJoystickAuxRcOverrideThreadSafe({}, {}, false); | ||
| (void) disconnect(this, nullptr, _pollingVehicle, nullptr); | ||
| (void) disconnect(_pollingVehicle, &Vehicle::flightModesChanged, this, &Joystick::_flightModesChanged); | ||
| if (GimbalController *const gimbal = _pollingVehicle->gimbalController()) { | ||
|
|
||
| Original file line number | Diff line number | Diff line change | ||||||||
|---|---|---|---|---|---|---|---|---|---|---|
|
|
@@ -4156,6 +4156,92 @@ void Vehicle::sendJoystickDataThreadSafe(float roll, float pitch, float yaw, flo | |||||||||
| sendMessageOnLinkThreadSafe(sharedLink.get(), message); | ||||||||||
| } | ||||||||||
|
|
||||||||||
| void Vehicle::sendJoystickAuxRcOverrideThreadSafe(const std::array<uint16_t, 6> &channelValues, const std::array<bool, 6> &channelEnabled, bool useRcOverride) | ||||||||||
| { | ||||||||||
| SharedLinkInterfacePtr sharedLink = vehicleLinkManager()->primaryLink().lock(); | ||||||||||
| if (!sharedLink) { | ||||||||||
| qCDebug(VehicleLog) << "sendJoystickAuxRcOverrideThreadSafe: primary link gone!"; | ||||||||||
| return; | ||||||||||
| } | ||||||||||
|
|
||||||||||
| if (sharedLink->linkConfiguration()->isHighLatency()) { | ||||||||||
| return; | ||||||||||
| } | ||||||||||
|
|
||||||||||
| bool anyEnabledChannel = false; | ||||||||||
| for (bool enabled : channelEnabled) { | ||||||||||
| if (enabled) { | ||||||||||
| anyEnabledChannel = true; | ||||||||||
| break; | ||||||||||
| } | ||||||||||
| } | ||||||||||
|
|
||||||||||
| if (!useRcOverride || !anyEnabledChannel) { | ||||||||||
| if (!_joystickAuxRcOverrideActive) { | ||||||||||
| return; | ||||||||||
| } | ||||||||||
|
|
||||||||||
| mavlink_message_t releaseMessage; | ||||||||||
| mavlink_msg_rc_channels_override_pack_chan( | ||||||||||
| static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()), | ||||||||||
| static_cast<uint8_t>(MAVLinkProtocol::getComponentId()), | ||||||||||
| sharedLink->mavlinkChannel(), | ||||||||||
| &releaseMessage, | ||||||||||
| static_cast<uint8_t>(_systemID), | ||||||||||
| static_cast<uint8_t>(_defaultComponentId), | ||||||||||
| UINT16_MAX, | ||||||||||
| UINT16_MAX, | ||||||||||
| UINT16_MAX, | ||||||||||
| UINT16_MAX, | ||||||||||
| 0, | ||||||||||
| 0, | ||||||||||
| 0, | ||||||||||
| 0, | ||||||||||
| static_cast<uint16_t>(UINT16_MAX - 1), | ||||||||||
| static_cast<uint16_t>(UINT16_MAX - 1), | ||||||||||
| 0, | ||||||||||
|
Comment on lines
+4198
to
+4202
|
||||||||||
| 0, | ||||||||||
| 0, | ||||||||||
| 0, | ||||||||||
| 0, | ||||||||||
| 0, | ||||||||||
| 0, | ||||||||||
| 0); | ||||||||||
| sendMessageOnLinkThreadSafe(sharedLink.get(), releaseMessage); | ||||||||||
| _joystickAuxRcOverrideActive = false; | ||||||||||
| return; | ||||||||||
| } | ||||||||||
|
|
||||||||||
| mavlink_message_t message; | ||||||||||
| mavlink_msg_rc_channels_override_pack_chan( | ||||||||||
| static_cast<uint8_t>(MAVLinkProtocol::instance()->getSystemId()), | ||||||||||
| static_cast<uint8_t>(MAVLinkProtocol::getComponentId()), | ||||||||||
| sharedLink->mavlinkChannel(), | ||||||||||
| &message, | ||||||||||
| static_cast<uint8_t>(_systemID), | ||||||||||
| static_cast<uint8_t>(_defaultComponentId), | ||||||||||
| UINT16_MAX, | ||||||||||
| UINT16_MAX, | ||||||||||
| UINT16_MAX, | ||||||||||
| UINT16_MAX, | ||||||||||
| channelEnabled[0] ? channelValues[0] : static_cast<uint16_t>(0), | ||||||||||
| channelEnabled[1] ? channelValues[1] : static_cast<uint16_t>(0), | ||||||||||
| channelEnabled[2] ? channelValues[2] : static_cast<uint16_t>(0), | ||||||||||
| channelEnabled[3] ? channelValues[3] : static_cast<uint16_t>(0), | ||||||||||
| channelEnabled[4] ? channelValues[4] : static_cast<uint16_t>(UINT16_MAX - 1), | ||||||||||
| channelEnabled[5] ? channelValues[5] : static_cast<uint16_t>(UINT16_MAX - 1), | ||||||||||
|
Comment on lines
+4231
to
+4232
|
||||||||||
| channelEnabled[4] ? channelValues[4] : static_cast<uint16_t>(UINT16_MAX - 1), | |
| channelEnabled[5] ? channelValues[5] : static_cast<uint16_t>(UINT16_MAX - 1), | |
| channelEnabled[4] ? channelValues[4] : static_cast<uint16_t>(0), | |
| channelEnabled[5] ? channelValues[5] : static_cast<uint16_t>(0), |
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
_adjustRangeToRcOverridePwmusesstd::lround, but this translation unit doesn’t include<cmath>. Depending on indirect includes, this can fail to compile (or compile inconsistently across platforms/compilers). Add the proper standard header forstd::lround.