Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
81 changes: 73 additions & 8 deletions src/Joystick/Joystick.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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();
Expand Down Expand Up @@ -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;
Expand All @@ -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) {
Expand All @@ -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
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

_adjustRangeToRcOverridePwm uses std::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 for std::lround.

Copilot uses AI. Check for mistakes.
Comment on lines +860 to +871
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The new PWM mapping path (_adjustRangeToRcOverridePwm) is untested. There are existing unit tests for _adjustRange, so it would be good to add tests that verify the 1000–2000µs mapping for both normal (-1..1) and one-sided (0..1) axes, including reversed calibration.

Copilot uses AI. Check for mistakes.

void Joystick::_handleAxis()
{
const int axisDelay = static_cast<int>(1000.0 / _joystickSettings.axisFrequencyHz()->rawValue().toDouble());
Expand Down Expand Up @@ -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 ||
Expand Down Expand Up @@ -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()) {
Expand All @@ -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()) {
Expand All @@ -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()) {
Expand All @@ -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()) {
Expand All @@ -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()) {
Expand All @@ -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) {
Expand Down Expand Up @@ -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
Expand All @@ -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);
}
}

Expand Down Expand Up @@ -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()) {
Expand Down
3 changes: 3 additions & 0 deletions src/Joystick/Joystick.h
Original file line number Diff line number Diff line change
Expand Up @@ -9,6 +9,8 @@
#include <QtGui/QVector3D>
#include <QtQmlIntegration/QtQmlIntegration>

#include <array>

#include "RemoteControlCalibrationController.h"
#include "Fact.h"
#include "JoystickSettings.h"
Expand Down Expand Up @@ -428,6 +430,7 @@ private slots:

/// Adjust the raw axis value to the -1:1 range given calibration information
float _adjustRange(int reversedAxisValue, const AxisCalibration_t &calibration, bool withDeadbands);
uint16_t _adjustRangeToRcOverridePwm(int value, const AxisCalibration_t &calibration, bool withDeadbands);

void _executeButtonAction(const QString &action, const ButtonEvent_t buttonEvent);
int _findAvailableButtonActionIndex(const QString &action);
Expand Down
7 changes: 7 additions & 0 deletions src/Settings/Joystick.SettingsGroup.json
Original file line number Diff line number Diff line change
Expand Up @@ -132,6 +132,13 @@
"default": false,
"label": "Enable manual control for Aux 6"
},
{
"name": "useRcOverrideForAuxChannels",
"shortDesc": "Use RC override for Aux channels",
"type": "bool",
"default": false,
"label": "Use RC override for Aux channels"
},
{
"name": "enableManualControlPitchExtension",
"shortDesc": "Enable manual control pitch extension",
Expand Down
1 change: 1 addition & 0 deletions src/Settings/JoystickSettings.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,5 +34,6 @@ DECLARE_SETTINGSFACT(JoystickSettings, enableManualControlAux3)
DECLARE_SETTINGSFACT(JoystickSettings, enableManualControlAux4)
DECLARE_SETTINGSFACT(JoystickSettings, enableManualControlAux5)
DECLARE_SETTINGSFACT(JoystickSettings, enableManualControlAux6)
DECLARE_SETTINGSFACT(JoystickSettings, useRcOverrideForAuxChannels)
DECLARE_SETTINGSFACT(JoystickSettings, enableManualControlPitchExtension)
DECLARE_SETTINGSFACT(JoystickSettings, enableManualControlRollExtension)
1 change: 1 addition & 0 deletions src/Settings/JoystickSettings.h
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@ class JoystickSettings : public SettingsGroup
DEFINE_SETTINGFACT(enableManualControlAux4)
DEFINE_SETTINGFACT(enableManualControlAux5)
DEFINE_SETTINGFACT(enableManualControlAux6)
DEFINE_SETTINGFACT(useRcOverrideForAuxChannels)

private:
QString _joystickName;
Expand Down
86 changes: 86 additions & 0 deletions src/Vehicle/Vehicle.cc
Original file line number Diff line number Diff line change
Expand Up @@ -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
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

The RC_CHANNELS_OVERRIDE packing uses UINT16_MAX - 1 (65534) for some “unused” channels (chan9/chan10), while other unused channels use 0. 65534 is not a standard MAVLink sentinel and is also far outside the valid 1000–2000µs PWM range, so if interpreted as an override it could produce an invalid command. Please use the MAVLink-defined ignore/release sentinel values consistently for all non-overridden channels (and consider using named constants to avoid mistakes).

Copilot uses AI. Check for mistakes.
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
Copy link

Copilot AI Apr 10, 2026

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Same concern in the active override message: when Aux5/Aux6 are disabled, the code sends UINT16_MAX - 1 for chan9/chan10. Please verify the correct MAVLink sentinel for “ignore/release” on these fields and use it consistently (avoid 65534 unless the spec explicitly defines it).

Suggested change
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),

Copilot uses AI. Check for mistakes.
0,
0,
0,
0,
0,
0,
0,
0);
sendMessageOnLinkThreadSafe(sharedLink.get(), message);
_joystickAuxRcOverrideActive = true;
}

void Vehicle::triggerSimpleCamera()
{
sendMavCommand(_defaultComponentId,
Expand Down
4 changes: 4 additions & 0 deletions src/Vehicle/Vehicle.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,8 @@
#include <QtPositioning/QGeoCoordinate>
#include <QtQmlIntegration/QtQmlIntegration>

#include <array>

#include "HealthAndArmingCheckReport.h"
#include "MAVLinkStreamConfig.h"
#include "QGCMapCircle.h"
Expand Down Expand Up @@ -423,6 +425,7 @@ class Vehicle : public VehicleFactGroup, public VehicleTypes
void updateFlightDistance(double distance);

void sendJoystickDataThreadSafe (float roll, float pitch, float yaw, float thrust, quint16 buttons, quint16 buttons2, float pitchExtension, float rollExtension, float aux1, float aux2, float aux3, float aux4, float aux5, float aux6);
void sendJoystickAuxRcOverrideThreadSafe(const std::array<uint16_t, 6> &channelValues, const std::array<bool, 6> &channelEnabled, bool useRcOverride);

// Property accesors
int id() const{ return _systemID; }
Expand Down Expand Up @@ -1009,6 +1012,7 @@ void _activeVehicleChanged (Vehicle* newActiveVehicle);
bool _readyToFly = false;
bool _allSensorsHealthy = true;
bool _mavlinkSigning = false;
bool _joystickAuxRcOverrideActive = false;
QString _mavlinkSigningKeyName;

SysStatusSensorInfo _sysStatusSensorInfo;
Expand Down
7 changes: 7 additions & 0 deletions src/Vehicle/VehicleSetup/JoystickComponentSettings.qml
Original file line number Diff line number Diff line change
Expand Up @@ -156,5 +156,12 @@ ColumnLayout {
fact: _joystickSettings.enableManualControlAux6
visible: fact.userVisible
}

FactCheckBoxSlider {
Layout.fillWidth: true
text: qsTr("RC_CHANNELS_OVERRIDE for AUX1-AUX6")
fact: _joystickSettings.useRcOverrideForAuxChannels
visible: fact.userVisible
}
}
}
6 changes: 6 additions & 0 deletions src/Vehicle/VehicleSetup/RemoteControlCalibration.qml
Original file line number Diff line number Diff line change
Expand Up @@ -220,6 +220,12 @@ ColumnLayout {
onClicked: controller.cancelButtonClicked()
}

QGCButton {
text: qsTr("Unable")
visible: controller.unableButtonVisible
onClicked: controller.unableButtonClicked()
}

QGCButton {
id: nextButton
primary: true
Expand Down
Loading
Loading