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
9 changes: 6 additions & 3 deletions src/AutoPilotPlugins/Common/RadioComponentController.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,15 +16,18 @@ RadioComponentController::RadioComponentController(QObject *parent)
// qCDebug(RadioComponentControllerLog) << Q_FUNC_INFO << this;

// Channels values are in PWM
_calValidMinValue = 1300;
_calValidMaxValue = 1700;
_calCenterPoint= ((_calValidMaxValue - _calValidMinValue) / 2.0f) + _calValidMinValue;

_calDefaultMinValue = 1000;
_calDefaultMaxValue = 2000;
_calCenterPoint= ((_calDefaultMaxValue - _calDefaultMinValue) / 2.0f) + _calDefaultMinValue;
_calRoughCenterDelta = 50;
_calMoveDelta = 300;
_calSettleDelta = 20;

int valueRange = _calDefaultMaxValue - _calDefaultMinValue;
_calValidMinValue = _calDefaultMinValue + (valueRange * 0.3f);
_calValidMaxValue = _calDefaultMaxValue - (valueRange * 0.3f);

// Deal with parameter differences between PX4 and Ardupilot
if (parameterExists(ParameterManager::defaultComponentId, QStringLiteral("RC1_REVERSED"))) {
// Newer ardupilot firmwares have a different reverse param naming scheme and value scheme
Expand Down
890 changes: 500 additions & 390 deletions src/Joystick/Joystick.cc

Large diffs are not rendered by default.

81 changes: 51 additions & 30 deletions src/Joystick/Joystick.h
Original file line number Diff line number Diff line change
Expand Up @@ -115,16 +115,30 @@ class Joystick : public QThread
int center = 0;
int deadband = 0;
bool reversed = false;

void reset() {
min = AxisMin;
max = AxisMax;
center = 0;
deadband = 0;
reversed = false;
}
};

enum AxisFunction_t {
rollFunction,
pitchFunction,
yawFunction,
throttleFunction,
gimbalPitchFunction,
gimbalYawFunction,
maxAxisFunction // If the value of this is changed, be sure to update JoystickAxis.SettingsGroup.json/stickFunction metadata
pitchExtensionFunction,
rollExtensionFunction,
aux1ExtensionFunction,
aux2ExtensionFunction,
aux3ExtensionFunction,
aux4ExtensionFunction,
aux5ExtensionFunction,
aux6ExtensionFunction,
maxAxisFunction
};
static QString axisFunctionToString(AxisFunction_t function);

Expand Down Expand Up @@ -297,8 +311,6 @@ class Joystick : public QThread
QString linkedGroupRole() const { return _linkedGroupRole; }
void setLinkedGroupRole(const QString &role);

void setFunctionAxis(AxisFunction_t function, int axis);
int getFunctionAxis(AxisFunction_t function) const;
void setAxisCalibration(int axis, const AxisCalibration_t &calibration);
Joystick::AxisCalibration_t getAxisCalibration(int axis) const;

Expand Down Expand Up @@ -365,9 +377,17 @@ class Joystick : public QThread
int _hatCount = 0;

private slots:
void _flightModesChanged() { _buildActionList(_pollingVehicle); }
void _flightModesChanged() { _buildAvailableButtonsActionList(_pollingVehicle); }

private:
enum PollingType {
NotPolling, ///< Not currrently polling
PollingForConfiguration, ///< Polling for configuration/calibration display
PollingForVehicle, ///< Normal polling for joystick output to Vehicle
};

using AxisFunctionMap_t = QMap<AxisFunction_t, int>;

virtual bool _open() = 0;
virtual void _close() = 0;
virtual bool _update() = 0;
Expand All @@ -378,12 +398,8 @@ private slots:

void run() override;

enum PollingType {
NotPolling, ///< Not currrently polling
PollingForConfiguration, ///< Polling for configuration/calibration display
PollingForVehicle, ///< Normal polling for joystick output to Vehicle
};
void _startPollingForVehicle(Vehicle &vehicle);
void _startPollingForActiveVehicle();
void _startPollingForConfiguration();
void _stopPollingForConfiguration();
void _stopAllPolling();
Expand All @@ -392,30 +408,40 @@ private slots:
PollingType _previousPollingType = NotPolling;
Vehicle* _pollingVehicle = nullptr;

void _resetFunctionToAxisMap();
void _resetAxisCalibrationData();
void _resetButtonActionData();
void _resetButtonEventStates();

void _foundInvalidAxisSettingsCleanup();

void _loadButtonSettings();
void _loadAxisSettings(bool calibrated, int transmitterMode);
void _saveButtonSettings();
void _saveAxisSettings(bool calibrated, int transmitterMode);
void _loadFromSettingsIntoCalibrationData();
void _saveFromCalibrationDataIntoSettings();
void _clearAxisSettings();
void _clearButtonSettings();

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

void _executeButtonAction(const QString &action, const ButtonEvent_t buttonEvent);
int _findAvailableButtonActionIndex(const QString &action);
bool _validAxis(int axis) const;
bool _validButton(int button) const;
void _handleAxis();
void _handleButtons();
void _buildActionList(Vehicle *vehicle);
AxisFunction_t _getFunctionForAxis(int axis) const;
void _buildAvailableButtonsActionList(Vehicle *vehicle);
AxisFunction_t _getAxisFunctionForJoystickAxis(int joystickAxis) const;
int _getJoystickAxisForAxisFunction(AxisFunction_t axisFunction) const;
void _setJoystickAxisForAxisFunction(AxisFunction_t axisFunction, int axis);
void _updateButtonEventState(int buttonIndex, const bool buttonPressed, ButtonEvent_t &buttonEventState);
void _updateButtonEventStates(QVector<ButtonEvent_t> &buttonEventStates);
void _migrateLegacySettings();


/// Relative mappings of axis functions between different TX modes
int _mapFunctionMode(int mode, int function);

/// Remap current axis functions from current TX mode to new TX mode
void _remapAxes(int fromMode, int toMode, int (&newMapping)[maxAxisFunction]);
void _remapFunctionsInFunctionMapToNewTransmittedMode(int fromMode, int toMode);

int _hatButtonCount = 0;
int _totalButtonCount = 0;
Expand All @@ -424,9 +450,13 @@ private slots:
QVector<AssignedButtonAction*> _assignedButtonActions;
MavlinkActionManager *_mavlinkActionManager = nullptr;
QmlObjectListModel *_availableButtonActions = nullptr;

JoystickManager* _joystickManager = nullptr;
JoystickSettings _joystickSettings;

int _rgFunctionAxis[maxAxisFunction] = {};
AxisFunctionMap_t _axisFunctionToJoystickAxisMap; ///< Map from AxisFunction_t to axis index, kJoystickAxisNotAssigned if not assigned
static constexpr const int kJoystickAxisNotAssigned = -1;

QElapsedTimer _axisElapsedTimer;
QStringList _availableActionTitles;
std::atomic<bool> _exitThread = false; ///< true: signal thread to exit
Expand All @@ -435,15 +465,6 @@ private slots:
QString _linkedGroupId;
QString _linkedGroupRole;

static constexpr const char *_rgFunctionSettingsKey[maxAxisFunction] = {
"RollAxis",
"PitchAxis",
"YawAxis",
"ThrottleAxis",
"GimbalPitchAxis",
"GimbalYawAxis"
};

static constexpr const char *_buttonActionNone = QT_TR_NOOP("No Action");
static constexpr const char *_buttonActionArm = QT_TR_NOOP("Arm");
static constexpr const char *_buttonActionDisarm = QT_TR_NOOP("Disarm");
Expand Down
51 changes: 42 additions & 9 deletions src/Joystick/JoystickManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -44,11 +44,13 @@ JoystickManager::JoystickManager(QObject *parent)
auto multiVehicleManager = MultiVehicleManager::instance();
auto activeVehicle = multiVehicleManager->activeVehicle();
if (activeVehicle && _activeJoystick) {
if (joystickEnabledForVehicle(activeVehicle)) {
_activeJoystick->_startPollingForVehicle(*activeVehicle);
if (_joystickEnabledForVehicle(activeVehicle)) {
_activeJoystick->_startPollingForActiveVehicle();
} else {
_activeJoystick->_stopAllPolling();
}
}
emit joystickEnabledChanged();
emit activeJoystickEnabledForActiveVehicleChanged();
});

(void) connect(MultiVehicleManager::instance(), &MultiVehicleManager::activeVehicleChanged, this, &JoystickManager::_activeVehicleChanged);
Expand Down Expand Up @@ -154,6 +156,23 @@ Joystick *JoystickManager::activeJoystick()
return _activeJoystick;
}

bool JoystickManager::activeJoystickEnabledForActiveVehicle() const
{
Vehicle *activeVehicle = MultiVehicleManager::instance()->activeVehicle();
if (!activeVehicle || !_activeJoystick) {
return false;
}
return _joystickEnabledForVehicle(activeVehicle);
}

void JoystickManager::setActiveJoystickEnabledForActiveVehicle(bool enabled)
{
Vehicle *activeVehicle = MultiVehicleManager::instance()->activeVehicle();
if (activeVehicle) {
_setJoystickEnabledForVehicle(activeVehicle, enabled);
}
}

void JoystickManager::_setActiveJoystick(Joystick *newActiveJoystick)
{
if (newActiveJoystick && !_name2JoystickMap.contains(newActiveJoystick->name())) {
Expand All @@ -165,6 +184,7 @@ void JoystickManager::_setActiveJoystick(Joystick *newActiveJoystick)
return;
}

// Cleanup old active joystick
if (_activeJoystick) {
_activeJoystick->_stopAllPolling();
_activeJoystick = nullptr;
Expand All @@ -179,11 +199,17 @@ void JoystickManager::_setActiveJoystick(Joystick *newActiveJoystick)
auto multiVehicleManager = MultiVehicleManager::instance();
auto activeVehicle = multiVehicleManager->activeVehicle();

if (activeVehicle && joystickEnabledForVehicle(activeVehicle)) {
_activeJoystick->_startPollingForVehicle(*activeVehicle);
if (activeVehicle) {
if (_activeJoystick->requiresCalibration() && _joystickEnabledForVehicle(activeVehicle)) {
qCWarning(JoystickManagerLog) << "Active joystick not calibrated but enabled, cannot start polling for active vehicle. Setting joystick for vehicle to disabled.";
setActiveJoystickEnabledForActiveVehicle(false);
} else if (_joystickEnabledForVehicle(activeVehicle)) {
_activeJoystick->_startPollingForActiveVehicle();
}
}

emit activeJoystickChanged(_activeJoystick);
emit activeJoystickEnabledForActiveVehicleChanged();
}
}

Expand All @@ -205,18 +231,25 @@ void JoystickManager::_activeVehicleChanged(Vehicle *activeVehicle)

_activeJoystick->_stopAllPolling();

if (activeVehicle && joystickEnabledForVehicle(activeVehicle)) {
_activeJoystick->_startPollingForVehicle(*activeVehicle);
if (activeVehicle && _joystickEnabledForVehicle(activeVehicle)) {
if (!_activeJoystick->settings()->calibrated()->rawValue().toBool()) {
qCWarning(JoystickManagerLog) << "Active joystick not calibrated but enabled, cannot start polling for active vehicle. Setting joystick to disabled.";
setActiveJoystickEnabledForActiveVehicle(false);
return;
}
_activeJoystick->_startPollingForActiveVehicle();
}

emit activeJoystickEnabledForActiveVehicleChanged();
}

bool JoystickManager::joystickEnabledForVehicle(Vehicle *vehicle) const
bool JoystickManager::_joystickEnabledForVehicle(Vehicle *vehicle) const
{
const QStringList vehicleIds = _joystickManagerSettings->joystickEnabledVehiclesIds()->rawValue().toString().split(",", Qt::SkipEmptyParts);
return vehicleIds.contains(QString::number(vehicle->id()));
}

void JoystickManager::setJoystickEnabledForVehicle(Vehicle *vehicle, bool enabled)
void JoystickManager::_setJoystickEnabledForVehicle(Vehicle *vehicle, bool enabled)
{
QStringList vehicleIds = _joystickManagerSettings->joystickEnabledVehiclesIds()->rawValue().toString().split(",", Qt::SkipEmptyParts);
const QString vehicleIdStr = QString::number(vehicle->id());
Expand Down
11 changes: 6 additions & 5 deletions src/Joystick/JoystickManager.h
Original file line number Diff line number Diff line change
Expand Up @@ -23,8 +23,8 @@ class JoystickManager : public QObject
/// Note: The active joystick name may be not in this list if the joystick is not currently connected
Q_PROPERTY(QStringList availableJoystickNames READ availableJoystickNames NOTIFY availableJoystickNamesChanged)

/// Currently active joystick
Q_PROPERTY(Joystick *activeJoystick READ activeJoystick NOTIFY activeJoystickChanged)
Q_PROPERTY(bool activeJoystickEnabledForActiveVehicle READ activeJoystickEnabledForActiveVehicle WRITE setActiveJoystickEnabledForActiveVehicle NOTIFY activeJoystickEnabledForActiveVehicleChanged)

/// Number of connected joysticks
Q_PROPERTY(int joystickCount READ joystickCount NOTIFY availableJoystickNamesChanged)
Expand All @@ -41,9 +41,8 @@ class JoystickManager : public QObject
int joystickCount() const { return _name2JoystickMap.count(); }

Joystick *activeJoystick();

Q_INVOKABLE bool joystickEnabledForVehicle(Vehicle *vehicle) const;
Q_INVOKABLE void setJoystickEnabledForVehicle(Vehicle *vehicle, bool enabled);
bool activeJoystickEnabledForActiveVehicle() const;
void setActiveJoystickEnabledForActiveVehicle(bool enabled);

/// Get all joysticks in a linked group
/// Returns empty list if groupId is empty or no matches found
Expand All @@ -54,8 +53,8 @@ class JoystickManager : public QObject

signals:
void activeJoystickChanged(Joystick *joystick);
void activeJoystickEnabledForActiveVehicleChanged();
void availableJoystickNamesChanged();
void joystickEnabledChanged();

public slots:
void init();
Expand All @@ -76,6 +75,8 @@ private slots:
private:
void _setActiveJoystickFromSettings();
void _setActiveJoystick(Joystick *joystick);
bool _joystickEnabledForVehicle(Vehicle *vehicle) const;
void _setJoystickEnabledForVehicle(Vehicle *vehicle, bool enabled);
Joystick *_findJoystickByInstanceId(int instanceId);
void _updatePollingTimer();

Expand Down
54 changes: 48 additions & 6 deletions src/Settings/Joystick.SettingsGroup.json
Original file line number Diff line number Diff line change
Expand Up @@ -62,12 +62,6 @@
"type": "bool",
"default": false
},
{
"name": "enableManualControlExtensions",
"shortDesc": "Enable manual control extensions",
"type": "bool",
"default": false
},
{
"name": "transmitterMode",
"shortDesc": "Transmitter mode (1-4)",
Expand All @@ -85,6 +79,54 @@
"max": 50,
"userMin": 0,
"userMax": 50
},
{
"name": "enableManualControlAux1",
"shortDesc": "Enable manual control for Aux 1",
"type": "bool",
"default": false
},
{
"name": "enableManualControlAux2",
"shortDesc": "Enable manual control for Aux 2",
"type": "bool",
"default": false
},
{
"name": "enableManualControlAux3",
"shortDesc": "Enable manual control for Aux 3",
"type": "bool",
"default": false
},
{
"name": "enableManualControlAux4",
"shortDesc": "Enable manual control for Aux 4",
"type": "bool",
"default": false
},
{
"name": "enableManualControlAux5",
"shortDesc": "Enable manual control for Aux 5",
"type": "bool",
"default": false
},
{
"name": "enableManualControlAux6",
"shortDesc": "Enable manual control for Aux 6",
"type": "bool",
"default": false
},
{
"name": "enableManualControlPitchExtension",
"shortDesc": "Enable manual control pitch extension",
"type": "bool",
"default": false
},
{
"name": "enableManualControlRollExtension",
"shortDesc": "Enable manual control roll extension",
"type": "bool",
"default": false
}
]
}
Loading
Loading