Commit 3ee54e56 authored by Gus Grubba's avatar Gus Grubba

Fix button state handling

Support up to 64 buttons, not limit to 16
Send a single button command and not a stream of commands at 25Hz
Send button commands through signals (it's coming from a different thread)
Hide gimbal support through analog channels (there are no MAVLink messages to handle it)
parent e28abddc
This diff is collapsed.
......@@ -60,31 +60,35 @@ public:
ThrottleModeMax
} ThrottleMode_t;
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(bool calibrated MEMBER _calibrated NOTIFY calibratedChanged)
Q_PROPERTY(int totalButtonCount READ totalButtonCount CONSTANT)
Q_PROPERTY(int axisCount READ axisCount CONSTANT)
Q_PROPERTY(QStringList actions READ actions CONSTANT)
Q_PROPERTY(QVariantList buttonActions READ buttonActions NOTIFY buttonActionsChanged)
Q_INVOKABLE void setButtonAction(int button, const QString& action);
Q_INVOKABLE QString getButtonAction(int button);
Q_PROPERTY(int throttleMode READ throttleMode WRITE setThrottleMode NOTIFY throttleModeChanged)
Q_PROPERTY(bool negativeThrust READ negativeThrust WRITE setNegativeThrust NOTIFY negativeThrustChanged)
Q_PROPERTY(float exponential READ exponential WRITE setExponential NOTIFY exponentialChanged)
Q_PROPERTY(bool accumulator READ accumulator WRITE setAccumulator NOTIFY accumulatorChanged)
Q_PROPERTY(bool requiresCalibration READ requiresCalibration CONSTANT)
Q_PROPERTY(bool circleCorrection READ circleCorrection WRITE setCircleCorrection NOTIFY circleCorrectionChanged)
Q_PROPERTY(float frequency READ frequency WRITE setFrequency NOTIFY frequencyChanged)
Q_PROPERTY(QString name READ name CONSTANT)
Q_PROPERTY(bool calibrated MEMBER _calibrated NOTIFY calibratedChanged)
Q_PROPERTY(int totalButtonCount READ totalButtonCount CONSTANT)
Q_PROPERTY(int axisCount READ axisCount CONSTANT)
Q_PROPERTY(bool requiresCalibration READ requiresCalibration CONSTANT)
Q_PROPERTY(QStringList actions READ actions CONSTANT)
Q_PROPERTY(QVariantList buttonActions READ buttonActions NOTIFY buttonActionsChanged)
Q_PROPERTY(bool gimbalEnabled READ gimbalEnabled WRITE setGimbalEnabled NOTIFY gimbalEnabledChanged)
Q_PROPERTY(int throttleMode READ throttleMode WRITE setThrottleMode NOTIFY throttleModeChanged)
Q_PROPERTY(float frequency READ frequency WRITE setFrequency NOTIFY frequencyChanged)
Q_PROPERTY(bool negativeThrust READ negativeThrust WRITE setNegativeThrust NOTIFY negativeThrustChanged)
Q_PROPERTY(float exponential READ exponential WRITE setExponential NOTIFY exponentialChanged)
Q_PROPERTY(bool accumulator READ accumulator WRITE setAccumulator NOTIFY accumulatorChanged)
Q_PROPERTY(bool circleCorrection READ circleCorrection WRITE setCircleCorrection NOTIFY circleCorrectionChanged)
Q_INVOKABLE void setButtonAction (int button, const QString& action);
Q_INVOKABLE QString getButtonAction (int button);
// Property accessors
int axisCount(void) { return _axisCount; }
int totalButtonCount(void) { return _totalButtonCount; }
QString name () { return _name; }
int totalButtonCount () { return _totalButtonCount; }
int axisCount () { return _axisCount; }
bool gimbalEnabled () { return _gimbalEnabled; }
QStringList actions ();
QVariantList buttonActions ();
void setGimbalEnabled (bool set);
/// Start the polling thread which will in turn emit joystick signals
void startPolling(Vehicle* vehicle);
......@@ -96,10 +100,7 @@ public:
void setFunctionAxis(AxisFunction_t function, int axis);
int getFunctionAxis(AxisFunction_t function);
QStringList actions(void);
QVariantList buttonActions(void);
QString name(void) { return _name; }
/*
// Joystick index used by sdl library
// Settable because sdl library remaps indices after certain events
......@@ -162,18 +163,26 @@ signals:
/// @param yaw Range is -1:1, negative meaning yaw left, positive meaning yaw right
/// @param throttle Range is 0:1, 0 meaning no throttle, 1 meaning full throttle
/// @param mode See Vehicle::JoystickMode_t enum
void manualControl (float roll, float pitch, float yaw, float throttle, quint16 buttons, int joystickMmode);
void manualControl (float roll, float pitch, float yaw, float throttle, quint16 buttons, int joystickMmode);
void manualControlGimbal (float gimbalPitch, float gimbalYaw);
void buttonActionTriggered(int action);
void frequencyChanged ();
void stepZoom (int direction);
void stepCamera (int direction);
void stepStream (int direction);
void triggerCamera ();
void startVideoRecord ();
void stopVideoRecord ();
void toggleVideoRecord ();
void gimbalEnabledChanged ();
void frequencyChanged ();
void stepZoom (int direction);
void stepCamera (int direction);
void stepStream (int direction);
void triggerCamera ();
void startVideoRecord ();
void stopVideoRecord ();
void toggleVideoRecord ();
void gimbalPitchStep (int direction);
void gimbalYawStep (int direction);
void centerGimbal ();
void setArmed (bool arm);
void setVtolInFwdFlight (bool set);
void setFlightMode (const QString& flightMode);
protected:
void _setDefaultCalibration ();
......@@ -185,29 +194,35 @@ protected:
bool _validButton (int button);
private:
virtual bool _open() = 0;
virtual void _close() = 0;
virtual bool _update() = 0;
virtual bool _open () = 0;
virtual void _close () = 0;
virtual bool _update () = 0;
virtual bool _getButton(int i) = 0;
virtual int _getAxis(int i) = 0;
virtual uint8_t _getHat(int hat,int i) = 0;
virtual bool _getButton (int i) = 0;
virtual int _getAxis (int i) = 0;
virtual bool _getHat (int hat,int i) = 0;
void _updateTXModeSettingsKey(Vehicle* activeVehicle);
int _mapFunctionMode(int mode, int function);
void _remapAxes(int currentMode, int newMode, int (&newMapping)[maxFunction]);
// Override from QThread
virtual void run(void);
virtual void run();
protected:
enum {
BUTTON_UP,
BUTTON_DOWN,
BUTTON_REPEAT
};
uint8_t*_rgButtonValues = nullptr;
bool _exitThread = false; ///< true: signal thread to exit
bool _calibrationMode = false;
int* _rgAxisValues = nullptr;
Calibration_t* _rgCalibration = nullptr;
bool* _rgButtonValues = nullptr;
quint16 _lastButtonBits = 0;
ThrottleMode_t _throttleMode = ThrottleModeDownZero;
bool _negativeThrust = false;
float _exponential = 0;
......@@ -216,7 +231,7 @@ protected:
bool _circleCorrection = true;
float _frequency = 25.0f;
Vehicle* _activeVehicle = nullptr;
bool _gimbalEnabled = false;
bool _pollingStartedForCalibration = false;
......@@ -234,7 +249,7 @@ protected:
QStringList _rgButtonActions;
MultiVehicleManager* _multiVehicleManager;
MultiVehicleManager* _multiVehicleManager = nullptr;
private:
static const char* _rgFunctionSettingsKey[maxFunction];
......@@ -254,6 +269,7 @@ private:
static const char* _roverTXModeSettingsKey;
static const char* _vtolTXModeSettingsKey;
static const char* _submarineTXModeSettingsKey;
static const char* _gimbalSettingsKey;
static const char* _buttonActionArm;
static const char* _buttonActionDisarm;
......
......@@ -200,11 +200,10 @@ int JoystickAndroid::_getAxis(int i) {
return axisValue[ i ];
}
uint8_t JoystickAndroid::_getHat(int hat,int i) {
bool JoystickAndroid::_getHat(int hat,int i) {
Q_UNUSED(hat);
Q_UNUSED(i);
return 0;
return false;
}
static JoystickManager *_manager = nullptr;
......
......@@ -29,13 +29,13 @@ private:
bool handleKeyEvent(jobject event);
bool handleGenericMotionEvent(jobject event);
virtual bool _open();
virtual void _close();
virtual bool _update();
virtual bool _open ();
virtual void _close ();
virtual bool _update ();
virtual bool _getButton(int i);
virtual int _getAxis(int i);
virtual uint8_t _getHat(int hat,int i);
virtual bool _getButton (int i);
virtual int _getAxis (int i);
virtual bool _getHat (int hat,int i);
int *btnCode;
int *axisCode;
......
......@@ -19,7 +19,6 @@ bool JoystickSDL::init(void) {
qWarning() << "Couldn't initialize SimpleDirectMediaLayer:" << SDL_GetError();
return false;
}
_loadGameControllerMappings();
return true;
}
......@@ -78,7 +77,7 @@ QMap<QString, Joystick*> JoystickSDL::discover(MultiVehicleManager* _multiVehicl
newRet[name] = new JoystickSDL(name, qMax(0,axisCount), qMax(0,buttonCount), qMax(0,hatCount), i, isGameController, _multiVehicleManager);
} else {
newRet[name] = ret[name];
JoystickSDL *j = (JoystickSDL*)newRet[name];
JoystickSDL *j = static_cast<JoystickSDL*>(newRet[name]);
if (j->index() != i) {
j->setIndex(i); // This joystick index has been remapped by SDL
}
......@@ -131,7 +130,7 @@ bool JoystickSDL::_open(void) {
}
void JoystickSDL::_close(void) {
if (sdlJoystick == NULL) {
if (sdlJoystick == nullptr) {
qCDebug(JoystickLog) << "Attempt to close null joystick!";
return;
}
......@@ -152,8 +151,8 @@ void JoystickSDL::_close(void) {
}
}
sdlJoystick = NULL;
sdlController = NULL;
sdlJoystick = nullptr;
sdlController = nullptr;
}
bool JoystickSDL::_update(void)
......@@ -164,26 +163,25 @@ bool JoystickSDL::_update(void)
}
bool JoystickSDL::_getButton(int i) {
if ( _isGameController ) {
return !!SDL_GameControllerGetButton(sdlController, SDL_GameControllerButton(i));
if (_isGameController) {
return SDL_GameControllerGetButton(sdlController, SDL_GameControllerButton(i)) == 1;
} else {
return !!SDL_JoystickGetButton(sdlJoystick, i);
return SDL_JoystickGetButton(sdlJoystick, i) == 1;
}
}
int JoystickSDL::_getAxis(int i) {
if ( _isGameController ) {
if (_isGameController) {
return SDL_GameControllerGetAxis(sdlController, SDL_GameControllerAxis(i));
} else {
return SDL_JoystickGetAxis(sdlJoystick, i);
}
}
uint8_t JoystickSDL::_getHat(int hat,int i) {
bool JoystickSDL::_getHat(int hat, int i) {
uint8_t hatButtons[] = {SDL_HAT_UP,SDL_HAT_DOWN,SDL_HAT_LEFT,SDL_HAT_RIGHT};
if ( i < int(sizeof(hatButtons)) ) {
return !!(SDL_JoystickGetHat(sdlJoystick, hat) & hatButtons[i]);
if (i < int(sizeof(hatButtons))) {
return (SDL_JoystickGetHat(sdlJoystick, hat) & hatButtons[i]) != 0;
}
return 0;
return false;
}
......@@ -24,16 +24,17 @@ public:
private:
static void _loadGameControllerMappings();
bool _open() final;
void _close() final;
bool _update() final;
bool _open () final;
void _close () final;
bool _update () final;
bool _getButton(int i) final;
int _getAxis(int i) final;
uint8_t _getHat(int hat,int i) final;
bool _getButton (int i) final;
int _getAxis (int i) final;
bool _getHat (int hat,int i) final;
SDL_Joystick* sdlJoystick;
SDL_GameController* sdlController;
SDL_Joystick *sdlJoystick;
SDL_GameController *sdlController;
bool _isGameController;
int _index; ///< Index for SDL_JoystickOpen
......
......@@ -3064,26 +3064,29 @@ void Vehicle::guidedModeOrbit(const QGeoCoordinate& centerCoord, double radius,
qgcApp()->showMessage(QStringLiteral("Orbit mode not supported by Vehicle."));
return;
}
if (capabilityBits() & MAV_PROTOCOL_CAPABILITY_COMMAND_INT) {
sendMavCommandInt(defaultComponentId(),
MAV_CMD_DO_ORBIT,
MAV_FRAME_GLOBAL,
true, // show error if fails
radius,
qQNaN(), // Use default velocity
0, // Vehicle points to center
qQNaN(), // reserved
centerCoord.latitude(), centerCoord.longitude(), amslAltitude);
sendMavCommandInt(
defaultComponentId(),
MAV_CMD_DO_ORBIT,
MAV_FRAME_GLOBAL,
true, // show error if fails
static_cast<float>(radius),
static_cast<float>(qQNaN()), // Use default velocity
0, // Vehicle points to center
static_cast<float>(qQNaN()), // reserved
centerCoord.latitude(), centerCoord.longitude(), static_cast<float>(amslAltitude));
} else {
sendMavCommand(defaultComponentId(),
MAV_CMD_DO_ORBIT,
true, // show error if fails
radius,
qQNaN(), // Use default velocity
0, // Vehicle points to center
qQNaN(), // reserved
centerCoord.latitude(), centerCoord.longitude(), amslAltitude);
sendMavCommand(
defaultComponentId(),
MAV_CMD_DO_ORBIT,
true, // show error if fails
static_cast<float>(radius),
static_cast<float>(qQNaN()), // Use default velocity
0, // Vehicle points to center
static_cast<float>(qQNaN()), // reserved
static_cast<float>(centerCoord.latitude()),
static_cast<float>(centerCoord.longitude()),
static_cast<float>(amslAltitude));
}
}
......@@ -3098,10 +3101,11 @@ void Vehicle::pauseVehicle(void)
void Vehicle::abortLanding(double climbOutAltitude)
{
sendMavCommand(defaultComponentId(),
MAV_CMD_DO_GO_AROUND,
true, // show error if fails
climbOutAltitude);
sendMavCommand(
defaultComponentId(),
MAV_CMD_DO_GO_AROUND,
true, // show error if fails
static_cast<float>(climbOutAltitude));
}
bool Vehicle::guidedMode(void) const
......@@ -3116,11 +3120,12 @@ void Vehicle::setGuidedMode(bool guidedMode)
void Vehicle::emergencyStop(void)
{
sendMavCommand(_defaultComponentId,
MAV_CMD_COMPONENT_ARM_DISARM,
true, // show error if fails
0.0f,
21196.0f); // Magic number for emergency stop
sendMavCommand(
_defaultComponentId,
MAV_CMD_COMPONENT_ARM_DISARM,
true, // show error if fails
0.0f,
21196.0f); // Magic number for emergency stop
}
void Vehicle::setCurrentMissionSequence(int seq)
......@@ -3129,13 +3134,14 @@ void Vehicle::setCurrentMissionSequence(int seq)
seq--;
}
mavlink_message_t msg;
mavlink_msg_mission_set_current_pack_chan(_mavlink->getSystemId(),
_mavlink->getComponentId(),
priorityLink()->mavlinkChannel(),
&msg,
id(),
_compID,
seq);
mavlink_msg_mission_set_current_pack_chan(
static_cast<uint8_t>(_mavlink->getSystemId()),
static_cast<uint8_t>(_mavlink->getComponentId()),
priorityLink()->mavlinkChannel(),
&msg,
static_cast<uint8_t>(id()),
_compID,
static_cast<uint8_t>(seq));
sendMessageOnLink(priorityLink(), msg);
}
......@@ -3147,13 +3153,13 @@ void Vehicle::sendMavCommand(int component, MAV_CMD command, bool showError, flo
entry.component = component;
entry.command = command;
entry.showError = showError;
entry.rgParam[0] = param1;
entry.rgParam[1] = param2;
entry.rgParam[2] = param3;
entry.rgParam[3] = param4;
entry.rgParam[4] = param5;
entry.rgParam[5] = param6;
entry.rgParam[6] = param7;
entry.rgParam[0] = static_cast<double>(param1);
entry.rgParam[1] = static_cast<double>(param2);
entry.rgParam[2] = static_cast<double>(param3);
entry.rgParam[3] = static_cast<double>(param4);
entry.rgParam[4] = static_cast<double>(param5);
entry.rgParam[5] = static_cast<double>(param6);
entry.rgParam[6] = static_cast<double>(param7);
_mavCommandQueue.append(entry);
......@@ -3172,13 +3178,13 @@ void Vehicle::sendMavCommandInt(int component, MAV_CMD command, MAV_FRAME frame,
entry.command = command;
entry.frame = frame;
entry.showError = showError;
entry.rgParam[0] = param1;
entry.rgParam[1] = param2;
entry.rgParam[2] = param3;
entry.rgParam[3] = param4;
entry.rgParam[0] = static_cast<double>(param1);
entry.rgParam[1] = static_cast<double>(param2);
entry.rgParam[2] = static_cast<double>(param3);
entry.rgParam[3] = static_cast<double>(param4);
entry.rgParam[4] = param5;
entry.rgParam[5] = param6;
entry.rgParam[6] = param7;
entry.rgParam[6] = static_cast<double>(param7);
_mavCommandQueue.append(entry);
......@@ -3367,8 +3373,7 @@ void Vehicle::_handleCommandAck(mavlink_message_t& message)
emit mavCommandResult(_id, message.compid, ack.command, ack.result, false /* noResponsefromVehicle */);
if (showError) {
QString commandName = _toolbox->missionCommandTree()->friendlyName((MAV_CMD)ack.command);
QString commandName = _toolbox->missionCommandTree()->friendlyName(static_cast<MAV_CMD>(ack.command));
switch (ack.result) {
case MAV_RESULT_TEMPORARILY_REJECTED:
qgcApp()->showMessage(tr("%1 command temporarily rejected").arg(commandName));
......@@ -4016,6 +4021,7 @@ void Vehicle::gimbalPitchStep(int direction)
void Vehicle::gimbalYawStep(int direction)
{
if(!_haveGimbalData) {
qDebug() << "Yaw:" << _curGinmbalYaw << direction << (_curGinmbalYaw + direction);
double y = static_cast<double>(_curGinmbalYaw + direction);
gimbalControlValue(static_cast<double>(_curGinmbalYaw), y);
}
......
......@@ -840,8 +840,8 @@ public:
QGeoCoordinate homePosition(void);
bool armed(void) { return _armed; }
void setArmed(bool armed);
bool armed () { return _armed; }
void setArmed (bool armed);
bool flightModeSetAvailable(void);
QStringList flightModes(void);
......@@ -1084,7 +1084,6 @@ public:
void _setFlying(bool flying);
void _setLanding(bool landing);
void setVtolInFwdFlight(bool vtolInFwdFlight);
void _setHomePosition(QGeoCoordinate& homeCoord);
void _setMaxProtoVersion (unsigned version);
......@@ -1101,6 +1100,9 @@ public:
qreal gimbalYaw () { return static_cast<qreal>(_curGinmbalYaw); }
bool gimbalData () { return _haveGimbalData; }
public slots:
void setVtolInFwdFlight (bool vtolInFwdFlight);
signals:
void allLinksInactive(Vehicle* vehicle);
void coordinateChanged(QGeoCoordinate coordinate);
......
......@@ -103,6 +103,30 @@ Item {
}
}
}
//---------------------------------------------------------------------
//-- Enable Gimbal
QGCLabel {
text: qsTr("Enable gimbal control (Experimental)")
visible: advancedSettings.checked
Layout.alignment: Qt.AlignVCenter
}
QGCCheckBox {
id: enabledGimbal
visible: advancedSettings.checked
enabled: _activeJoystick
onClicked: _activeJoystick.gimbalEnabled = checked
Component.onCompleted: {
checked = _activeJoystick.gimbalEnabled
}
Connections {
target: joystickManager
onActiveJoystickChanged: {
if(_activeJoystick) {
enabledGimbal.checked = Qt.binding(function() { return _activeJoystick.gimbalEnabled })
}
}
}
}
//-----------------------------------------------------------------
//-- Mode
QGCLabel {
......
......@@ -96,7 +96,7 @@ Item {
width: ScreenTools.defaultFontPixelWidth * 0.125
height: parent.height * 0.2
color: qgcPal.text
visible: controller.hasGimbal
visible: controller.hasGimbalPitch && _activeJoystick.gimbalEnabled
x: (parent.width * 0.5) - (width * 0.5)
y: (parent.height * 0.5) - (height * 0.5)
}
......@@ -105,7 +105,7 @@ Item {
width: parent.width * 0.035
height: width
radius: width * 0.5
visible: controller.hasGimbal
visible: controller.hasGimbalPitch && _activeJoystick.gimbalEnabled
x: (parent.width * controller.gimbalPositions[0]) - (width * 0.5)
y: (parent.height * controller.gimbalPositions[1]) - (height * 0.5)
}
......@@ -115,7 +115,7 @@ Item {
width: parent.width * 0.2
height: ScreenTools.defaultFontPixelWidth * 0.125
color: qgcPal.text
visible: controller.hasGimbal
visible: controller.hasGimbalYaw && _activeJoystick.gimbalEnabled
x: (parent.width * 0.5) - (width * 0.5)
y: (parent.height * 0.3) - (height * 0.5)
}
......@@ -124,7 +124,7 @@ Item {
width: parent.width * 0.035
height: width
radius: width * 0.5
visible: controller.hasGimbal
visible: controller.hasGimbalYaw && _activeJoystick.gimbalEnabled
x: (parent.width * controller.gimbalPositions[2]) - (width * 0.5)
y: (parent.height * controller.gimbalPositions[3]) - (height * 0.5)
}
......
......@@ -12,8 +12,6 @@
#include "JoystickManager.h"
#include "QGCApplication.h"
#include <QSettings>
QGC_LOGGING_CATEGORY(JoystickConfigControllerLog, "JoystickConfigControllerLog")
const int JoystickConfigController::_calCenterPoint = 0;
......@@ -167,9 +165,14 @@ void JoystickConfigController::_advanceState()
{
_currentStep++;
const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
while (state->channelID > _axisCount) {
_currentStep++;
state = _getStateMachineEntry(_currentStep);
//-- Handle Gimbal
if (state->channelID > _axisCount) {
//-- No channels for gimbal
_advanceState();
}
if((state->channelID == 4 || state->channelID == 5) && !_activeJoystick->gimbalEnabled()) {
//-- Gimbal disabled. Skip it.
_advanceState();
}
_setupCurrentState();
}
......@@ -220,7 +223,10 @@ void JoystickConfigController::_axisValueChanged(int axis, int value)
// Track the axis count by keeping track of how many axes we see
if (axis + 1 > static_cast<int>(_axisCount)) {
_axisCount = axis + 1;
emit hasGimbalChanged();
if(_axisCount > 4)
emit hasGimbalPitchChanged();
if(_axisCount > 5)
emit hasGimbalYawChanged();
}
}
if (_currentStep != -1) {
......@@ -631,8 +637,8 @@ void JoystickConfigController::_setStickPositions()
_sticksYawRight = stLeftStickRight;
_sticksRollLeft = stRightStickLeft;
_sticksRollRight = stRightStickRight;
_sticksPitchUp = stLeftStickDown;
_sticksPitchDown = stLeftStickUp;
_sticksPitchUp = stLeftStickUp;
_sticksPitchDown = stLeftStickDown;
break;
case 2:
_sticksThrottleUp = stLeftStickUp;
......@@ -641,8 +647,8 @@ void JoystickConfigController::_setStickPositions()
_sticksYawRight = stLeftStickRight;
_sticksRollLeft = stRightStickLeft;
_sticksRollRight = stRightStickRight;
_sticksPitchUp = stRightStickDown;
_sticksPitchDown = stRightStickUp;
_sticksPitchUp = stRightStickUp;
_sticksPitchDown = stRightStickDown;
break;
case 3:
_sticksThrottleUp = stRightStickUp;
......@@ -651,8 +657,8 @@ void JoystickConfigController::_setStickPositions()
_sticksYawRight = stRightStickRight;
_sticksRollLeft = stLeftStickLeft;
_sticksRollRight = stLeftStickRight;
_sticksPitchUp = stLeftStickDown;
_sticksPitchDown = stLeftStickUp;
_sticksPitchUp = stLeftStickUp;
_sticksPitchDown = stLeftStickDown;
break;
case 4:
_sticksThrottleUp = stLeftStickUp;
......@@ -661,8 +667,8 @@ void JoystickConfigController::_setStickPositions()
_sticksYawRight = stRightStickRight;
_sticksRollLeft = stLeftStickLeft;
_sticksRollRight = stLeftStickRight;
_sticksPitchUp = stRightStickDown;
_sticksPitchDown = stRightStickUp;
_sticksPitchUp = stRightStickUp;
_sticksPitchDown = stRightStickDown;
break;
default:
Q_ASSERT(false);
......@@ -766,7 +772,8 @@ void JoystickConfigController::_activeJoystickChanged(Joystick* joystick)
delete[] _axisRawValue;
_axisCount = 0;
_activeJoystick = nullptr;
emit hasGimbalChanged();
emit hasGimbalPitchChanged();
emit hasGimbalYawChanged();
}
if (joystick) {
......@@ -781,7 +788,8 @@ void JoystickConfigController::_activeJoystickChanged(Joystick* joystick)
_axisRawValue = new int[_axisCount];
_setInternalCalibrationValuesFromSettings();
connect(_activeJoystick, &Joystick::rawAxisValueChanged, this, &JoystickConfigController::_axisValueChanged);
emit hasGimbalChanged();
emit hasGimbalPitchChanged();
emit hasGimbalYawChanged();
}
}
......
......@@ -46,7 +46,9 @@ public:
Q_PROPERTY(bool yawAxisMapped READ yawAxisMapped NOTIFY yawAxisMappedChanged)
Q_PROPERTY(bool throttleAxisMapped READ throttleAxisMapped NOTIFY throttleAxisMappedChanged)
Q_PROPERTY(bool hasGimbal READ hasGimbal NOTIFY hasGimbalChanged)
Q_PROPERTY(bool hasGimbalPitch READ hasGimbalPitch NOTIFY hasGimbalPitchChanged)
Q_PROPERTY(bool hasGimbalYaw READ hasGimbalYaw NOTIFY hasGimbalYawChanged)
Q_PROPERTY(bool gimbalPitchAxisMapped READ gimbalPitchAxisMapped NOTIFY gimbalPitchAxisMappedChanged)
Q_PROPERTY(bool gimbalYawAxisMapped READ gimbalYawAxisMapped NOTIFY gimbalYawAxisMappedChanged)
......@@ -90,7 +92,8 @@ public:
bool gimbalPitchAxisReversed ();
bool gimbalYawAxisReversed ();
bool hasGimbal () { return _axisCount > 5; }
bool hasGimbalPitch () { return _axisCount > 4; }
bool hasGimbalYaw () { return _axisCount > 5; }
bool getDeadbandToggle ();
void setDeadbandToggle (bool);
......@@ -136,7 +139,8 @@ signals:
void skipEnabledChanged ();
void stickPositionsChanged ();
void gimbalPositionsChanged ();
void hasGimbalChanged ();
void hasGimbalPitchChanged ();
void hasGimbalYawChanged ();
void statusTextChanged ();
// @brief Signalled when in unit test mode and a message box should be displayed by the next button
......
......@@ -149,6 +149,7 @@ Item {
anchors.centerIn: parent
QGCLabel {
text: activeVehicle.sub ? qsTr("Lateral") : qsTr("Roll")
Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 12
}
AxisMonitor {
id: rollAxis
......@@ -156,10 +157,6 @@ Item {
width: axisMonitorWidth
mapped: controller.rollAxisMapped
reversed: controller.rollAxisReversed
Connections {
target: _activeJoystick
onManualControl: rollAxis.axisValue = roll * 32768.0
}
}
QGCLabel {
......@@ -173,10 +170,6 @@ Item {
width: axisMonitorWidth
mapped: controller.pitchAxisMapped
reversed: controller.pitchAxisReversed
Connections {
target: _activeJoystick
onManualControl: pitchAxis.axisValue = pitch * 32768.0
}
}
QGCLabel {
......@@ -190,10 +183,6 @@ Item {
width: axisMonitorWidth
mapped: controller.yawAxisMapped
reversed: controller.yawAxisReversed
Connections {
target: _activeJoystick
onManualControl: yawAxis.axisValue = yaw * 32768.0
}
}
QGCLabel {
......@@ -207,9 +196,15 @@ Item {
width: axisMonitorWidth
mapped: controller.throttleAxisMapped
reversed: controller.throttleAxisReversed
Connections {
target: _activeJoystick
onManualControl: throttleAxis.axisValue = _activeJoystick.negativeThrust ? throttle * -32768.0 : (-2 * throttle + 1) * 32768.0
}
Connections {
target: _activeJoystick
onManualControl: {
rollAxis.axisValue = roll * 32768.0
pitchAxis.axisValue = pitch * 32768.0
yawAxis.axisValue = yaw * 32768.0
throttleAxis.axisValue = _activeJoystick.negativeThrust ? throttle * -32768.0 : (-2 * throttle + 1) * 32768.0
}
}
......@@ -217,7 +212,7 @@ Item {
id: gimbalPitchLabel
width: _attitudeLabelWidth
text: qsTr("Gimbal Pitch")
visible: controller.hasGimbal
visible: controller.hasGimbalPitch && _activeJoystick.gimbalEnabled
}
AxisMonitor {
id: gimbalPitchAxis
......@@ -225,18 +220,14 @@ Item {
width: axisMonitorWidth
mapped: controller.gimbalPitchAxisMapped
reversed: controller.gimbalPitchAxisReversed
visible: controller.hasGimbal
Connections {
target: _activeJoystick
onManualControl: gimbalPitchAxis.axisValue = gimbalPitch * 32768.0
}
visible: controller.hasGimbalPitch && _activeJoystick.gimbalEnabled
}
QGCLabel {
id: gimbalYawLabel
width: _attitudeLabelWidth
text: qsTr("Gimbal Yaw")
visible: controller.hasGimbal
visible: controller.hasGimbalYaw && _activeJoystick.gimbalEnabled
}
AxisMonitor {
id: gimbalYawAxis
......@@ -244,9 +235,14 @@ Item {
width: axisMonitorWidth
mapped: controller.gimbalYawAxisMapped
reversed: controller.gimbalYawAxisReversed
Connections {
target: _activeJoystick
onManualControl: gimbalYawAxis.axisValue = gimbalYaw * 32768.0
visible: controller.hasGimbalYaw && _activeJoystick.gimbalEnabled
}
Connections {
target: _activeJoystick
onManualControlGimbal: {
gimbalPitchAxis.axisValue = gimbalPitch * 32768.0
gimbalYawAxis.axisValue = gimbalYaw * 32768.0
}
}
}
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment