Browse Source

Remove incomplete gimbal code (#9285)

QGC4.4
Don Gagne 4 years ago committed by GitHub
parent
commit
50e7665399
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
  1. 16
      src/Joystick/Joystick.cc
  2. 12
      src/Joystick/Joystick.h
  3. 24
      src/VehicleSetup/JoystickConfigAdvanced.qml
  4. 38
      src/VehicleSetup/JoystickConfigCalibration.qml
  5. 110
      src/VehicleSetup/JoystickConfigController.cc
  6. 27
      src/VehicleSetup/JoystickConfigController.h
  7. 38
      src/VehicleSetup/JoystickConfigGeneral.qml

16
src/Joystick/Joystick.cc

@ -39,7 +39,6 @@ const char* Joystick::_multiRotorTXModeSettingsKey = "TXMode_MultiRotor"; @@ -39,7 +39,6 @@ const char* Joystick::_multiRotorTXModeSettingsKey = "TXMode_MultiRotor";
const char* Joystick::_roverTXModeSettingsKey = "TXMode_Rover";
const char* Joystick::_vtolTXModeSettingsKey = "TXMode_VTOL";
const char* Joystick::_submarineTXModeSettingsKey = "TXMode_Submarine";
const char* Joystick::_gimbalSettingsKey = "GimbalEnabled";
const char* Joystick::_buttonActionNone = QT_TR_NOOP("No Action");
const char* Joystick::_buttonActionArm = QT_TR_NOOP("Arm");
@ -232,7 +231,6 @@ void Joystick::_loadSettings() @@ -232,7 +231,6 @@ void Joystick::_loadSettings()
_axisFrequencyHz = settings.value(_axisFrequencySettingsKey, _defaultAxisFrequencyHz).toFloat();
_buttonFrequencyHz = settings.value(_buttonFrequencySettingsKey, _defaultButtonFrequencyHz).toFloat();
_circleCorrection = settings.value(_circleCorrectionSettingsKey, false).toBool();
_gimbalEnabled = settings.value(_gimbalSettingsKey, false).toBool();
_throttleMode = static_cast<ThrottleMode_t>(settings.value(_throttleModeSettingsKey, ThrottleModeDownZero).toInt(&convertOk));
badSettings |= !convertOk;
@ -336,7 +334,6 @@ void Joystick::_saveSettings() @@ -336,7 +334,6 @@ void Joystick::_saveSettings()
settings.setValue(_axisFrequencySettingsKey, _axisFrequencyHz);
settings.setValue(_buttonFrequencySettingsKey, _buttonFrequencyHz);
settings.setValue(_throttleModeSettingsKey, _throttleMode);
settings.setValue(_gimbalSettingsKey, _gimbalEnabled);
settings.setValue(_circleCorrectionSettingsKey, _circleCorrection);
qCDebug(JoystickLog) << "_saveSettings calibrated:throttlemode:deadband:txmode" << _calibrated << _throttleMode << _deadband << _circleCorrection << _transmitterMode;
@ -668,12 +665,6 @@ void Joystick::_handleAxis() @@ -668,12 +665,6 @@ void Joystick::_handleAxis()
}
uint16_t shortButtons = static_cast<uint16_t>(buttonPressedBits & 0xFFFF);
_activeVehicle->sendJoystickDataThreadSafe(roll, pitch, yaw, throttle, shortButtons);
emit axisValues(roll, -pitch, yaw, throttle); // Used by joystick cal screen
if(_activeVehicle && _axisCount > 4 && _gimbalEnabled) {
//-- TODO: There is nothing consuming this as there are no messages to handle gimbal
// the way MANUAL_CONTROL handles the other channels.
emit manualControlGimbal((gimbalPitch + 1.0f) / 2.0f * 90.0f, gimbalYaw * 180.0f);
}
}
}
}
@ -935,13 +926,6 @@ void Joystick::setCircleCorrection(bool circleCorrection) @@ -935,13 +926,6 @@ void Joystick::setCircleCorrection(bool circleCorrection)
emit circleCorrectionChanged(_circleCorrection);
}
void Joystick::setGimbalEnabled(bool set)
{
_gimbalEnabled = set;
_saveSettings();
emit gimbalEnabledChanged();
}
void Joystick::setAxisFrequency(float val)
{
//-- Arbitrary limits

12
src/Joystick/Joystick.h

@ -99,7 +99,6 @@ public: @@ -99,7 +99,6 @@ public:
Q_PROPERTY(QStringList assignableActionTitles READ assignableActionTitles NOTIFY assignableActionsChanged)
Q_PROPERTY(QString disabledActionName READ disabledActionName CONSTANT)
Q_PROPERTY(bool gimbalEnabled READ gimbalEnabled WRITE setGimbalEnabled NOTIFY gimbalEnabledChanged)
Q_PROPERTY(int throttleMode READ throttleMode WRITE setThrottleMode NOTIFY throttleModeChanged)
Q_PROPERTY(float axisFrequencyHz READ axisFrequencyHz WRITE setAxisFrequency NOTIFY axisFrequencyHzChanged)
Q_PROPERTY(float minAxisFrequencyHz MEMBER _minAxisFrequencyHz CONSTANT)
@ -122,15 +121,12 @@ public: @@ -122,15 +121,12 @@ public:
QString name () { return _name; }
int totalButtonCount () { return _totalButtonCount; }
int axisCount () { return _axisCount; }
bool gimbalEnabled () { return _gimbalEnabled; }
QStringList buttonActions ();
QmlObjectListModel* assignableActions () { return &_assignableButtonActions; }
QStringList assignableActionTitles () { return _availableActionTitles; }
QString disabledActionName () { return _buttonActionNone; }
void setGimbalEnabled (bool set);
/// Start the polling thread which will in turn emit joystick signals
void startPolling(Vehicle* vehicle);
void stopPolling(void);
@ -198,11 +194,9 @@ signals: @@ -198,11 +194,9 @@ signals:
void enabledChanged (bool enabled);
void circleCorrectionChanged (bool circleCorrection);
void axisValues (float roll, float pitch, float yaw, float throttle);
void manualControlGimbal (float gimbalPitch, float gimbalYaw);
void gimbalEnabledChanged ();
void axisFrequencyHzChanged ();
void buttonFrequencyHzChanged ();
void axisFrequencyHzChanged ();
void buttonFrequencyHzChanged ();
void startContinuousZoom (int direction);
void stopContinuousZoom ();
void stepZoom (int direction);
@ -282,7 +276,6 @@ protected: @@ -282,7 +276,6 @@ protected:
float _axisFrequencyHz = _defaultAxisFrequencyHz;
float _buttonFrequencyHz = _defaultButtonFrequencyHz;
Vehicle* _activeVehicle = nullptr;
bool _gimbalEnabled = false;
bool _pollingStartedForCalibration = false;
@ -328,7 +321,6 @@ private: @@ -328,7 +321,6 @@ private:
static const char* _roverTXModeSettingsKey;
static const char* _vtolTXModeSettingsKey;
static const char* _submarineTXModeSettingsKey;
static const char* _gimbalSettingsKey;
static const char* _buttonActionNone;
static const char* _buttonActionArm;

24
src/VehicleSetup/JoystickConfigAdvanced.qml

@ -103,30 +103,6 @@ Item { @@ -103,30 +103,6 @@ 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 })
}
}
}
}
//-----------------------------------------------------------------
//-- Axis Message Frequency
QGCLabel {

38
src/VehicleSetup/JoystickConfigCalibration.qml

@ -90,44 +90,6 @@ Item { @@ -90,44 +90,6 @@ Item {
x: (parent.width * controller.stickPositions[2]) - (width * 0.5)
y: (parent.height * controller.stickPositions[3]) - (height * 0.5)
}
//---------------------------------------------------------
//-- Gimbal Pitch
Rectangle {
width: ScreenTools.defaultFontPixelWidth * 0.125
height: parent.height * 0.2
color: qgcPal.text
visible: controller.hasGimbalPitch && _activeJoystick.gimbalEnabled
x: (parent.width * 0.5) - (width * 0.5)
y: (parent.height * 0.5) - (height * 0.5)
}
Rectangle {
color: qgcPal.colorGreen
width: parent.width * 0.035
height: width
radius: width * 0.5
visible: controller.hasGimbalPitch && _activeJoystick.gimbalEnabled
x: (parent.width * controller.gimbalPositions[0]) - (width * 0.5)
y: (parent.height * controller.gimbalPositions[1]) - (height * 0.5)
}
//---------------------------------------------------------
//-- Gimbal Yaw
Rectangle {
width: parent.width * 0.2
height: ScreenTools.defaultFontPixelWidth * 0.125
color: qgcPal.text
visible: controller.hasGimbalYaw && _activeJoystick.gimbalEnabled
x: (parent.width * 0.5) - (width * 0.5)
y: (parent.height * 0.3) - (height * 0.5)
}
Rectangle {
color: qgcPal.colorGreen
width: parent.width * 0.035
height: width
radius: width * 0.5
visible: controller.hasGimbalYaw && _activeJoystick.gimbalEnabled
x: (parent.width * controller.gimbalPositions[2]) - (width * 0.5)
y: (parent.height * controller.gimbalPositions[3]) - (height * 0.5)
}
}
}
//---------------------------------------------------------------------

110
src/VehicleSetup/JoystickConfigController.cc

@ -14,8 +14,6 @@ @@ -14,8 +14,6 @@
QGC_LOGGING_CATEGORY(JoystickConfigControllerLog, "JoystickConfigControllerLog")
#define ENABLE_GIMBAL 0
const int JoystickConfigController::_calCenterPoint = 0;
const int JoystickConfigController::_calValidMinValue = -32768; ///< Largest valid minimum axis value
const int JoystickConfigController::_calValidMaxValue = 32767; ///< Smallest valid maximum axis value
@ -64,30 +62,6 @@ static const JoystickConfigController::stateStickPositions stRightStickRight { @@ -64,30 +62,6 @@ static const JoystickConfigController::stateStickPositions stRightStickRight {
0.25, 0.5, 0.8423, 0.5
};
//-- Gimbal
static const JoystickConfigController::stateStickPositions stGimbalCentered {
0.5, 0.5, 0.5, 0.3
};
#if ENABLE_GIMBAL
static const JoystickConfigController::stateStickPositions stGimbalPitchDown {
0.5, 0.6, 0.5, 0.3
};
static const JoystickConfigController::stateStickPositions stGimbalPitchUp {
0.5, 0.4, 0.5, 0.3
};
static const JoystickConfigController::stateStickPositions stGimbalYawLeft {
0.5, 0.5, 0.4, 0.3
};
static const JoystickConfigController::stateStickPositions stGimbalYawRight {
0.5, 0.5, 0.6, 0.3
};
#endif
JoystickConfigController::JoystickConfigController(void)
: _joystickManager(qgcApp()->toolbox()->joystickManager())
{
@ -97,7 +71,6 @@ JoystickConfigController::JoystickConfigController(void) @@ -97,7 +71,6 @@ JoystickConfigController::JoystickConfigController(void)
_setStickPositions();
_resetInternalCalibrationValues();
_currentStickPositions << _sticksCentered.leftX << _sticksCentered.leftY << _sticksCentered.rightX << _sticksCentered.rightY;
_currentGimbalPositions << stGimbalCentered.leftX << stGimbalCentered.leftY << stGimbalCentered.rightX << stGimbalCentered.rightY;
}
void JoystickConfigController::start(void)
@ -134,33 +107,21 @@ const JoystickConfigController::stateMachineEntry* JoystickConfigController::_ge @@ -134,33 +107,21 @@ const JoystickConfigController::stateMachineEntry* JoystickConfigController::_ge
static const char* msgPitchDown = "Move the Pitch stick all the way down and hold it there...";
static const char* msgPitchUp = "Move the Pitch stick all the way up and hold it there...";
static const char* msgPitchCenter = "Allow the Pitch stick to move back to center...";
#if ENABLE_GIMBAL
static const char* msgGimbalPitchDown = "Move the Gimbal Pitch control all the way down and hold it there...";
static const char* msgGimbalPitchUp = "Move the Gimbal Pitch control all the way up and hold it there...";
static const char* msgGimbalYawLeft = "Move the Gimbal Yaw control all the way to the left and hold it there...";
static const char* msgGimbalYawRight = "Move the Gimbal Yaw control all the way to the right and hold it there...";
#endif
static const char* msgComplete = "All settings have been captured.\nClick Next to enable the joystick.";
static const stateMachineEntry rgStateMachine[] = {
//Function
{ Joystick::maxFunction, msgBegin, _sticksCentered, stGimbalCentered, &JoystickConfigController::_inputCenterWaitBegin, &JoystickConfigController::_saveAllTrims, nullptr, 0 },
{ Joystick::throttleFunction, msgThrottleUp, _sticksThrottleUp, stGimbalCentered, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 0 },
{ Joystick::throttleFunction, msgThrottleDown, _sticksThrottleDown, stGimbalCentered, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 0 },
{ Joystick::yawFunction, msgYawRight, _sticksYawRight, stGimbalCentered, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 1 },
{ Joystick::yawFunction, msgYawLeft, _sticksYawLeft, stGimbalCentered, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 1 },
{ Joystick::rollFunction, msgRollRight, _sticksRollRight, stGimbalCentered, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 2 },
{ Joystick::rollFunction, msgRollLeft, _sticksRollLeft, stGimbalCentered, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 2 },
{ Joystick::pitchFunction, msgPitchUp, _sticksPitchUp, stGimbalCentered, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 3 },
{ Joystick::pitchFunction, msgPitchDown, _sticksPitchDown, stGimbalCentered, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 3 },
{ Joystick::pitchFunction, msgPitchCenter, _sticksCentered, stGimbalCentered, &JoystickConfigController::_inputCenterWait, nullptr, nullptr, 3 },
#if ENABLE_GIMBAL
{ Joystick::gimbalPitchFunction, msgGimbalPitchUp, _sticksCentered, stGimbalPitchUp, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 4 },
{ Joystick::gimbalPitchFunction, msgGimbalPitchDown, _sticksCentered, stGimbalPitchDown, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 4 },
{ Joystick::gimbalYawFunction, msgGimbalYawRight, _sticksCentered, stGimbalYawRight, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 5 },
{ Joystick::gimbalYawFunction, msgGimbalYawLeft, _sticksCentered, stGimbalYawLeft, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 5 },
#endif
{ Joystick::maxFunction, msgComplete, _sticksCentered, stGimbalCentered, nullptr, &JoystickConfigController::_writeCalibration, nullptr, -1 },
{ Joystick::maxFunction, msgBegin, _sticksCentered, &JoystickConfigController::_inputCenterWaitBegin, &JoystickConfigController::_saveAllTrims, nullptr, 0 },
{ Joystick::throttleFunction, msgThrottleUp, _sticksThrottleUp, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 0 },
{ Joystick::throttleFunction, msgThrottleDown, _sticksThrottleDown, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 0 },
{ Joystick::yawFunction, msgYawRight, _sticksYawRight, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 1 },
{ Joystick::yawFunction, msgYawLeft, _sticksYawLeft, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 1 },
{ Joystick::rollFunction, msgRollRight, _sticksRollRight, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 2 },
{ Joystick::rollFunction, msgRollLeft, _sticksRollLeft, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 2 },
{ Joystick::pitchFunction, msgPitchUp, _sticksPitchUp, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 3 },
{ Joystick::pitchFunction, msgPitchDown, _sticksPitchDown, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 3 },
{ Joystick::pitchFunction, msgPitchCenter, _sticksCentered, &JoystickConfigController::_inputCenterWait, nullptr, nullptr, 3 },
{ Joystick::maxFunction, msgComplete, _sticksCentered, nullptr, &JoystickConfigController::_writeCalibration, nullptr, -1 },
};
Q_ASSERT(step >= 0 && step < static_cast<int>((sizeof(rgStateMachine) / sizeof(rgStateMachine[0]))));
@ -170,19 +131,6 @@ const JoystickConfigController::stateMachineEntry* JoystickConfigController::_ge @@ -170,19 +131,6 @@ const JoystickConfigController::stateMachineEntry* JoystickConfigController::_ge
void JoystickConfigController::_advanceState()
{
_currentStep++;
#if ENABLE_GIMBAL
// TODO There are no MAVLink messages to handle gimbal from this
const stateMachineEntry* 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();
}
#endif
_setupCurrentState();
}
@ -214,10 +162,7 @@ void JoystickConfigController::_setupCurrentState() @@ -214,10 +162,7 @@ void JoystickConfigController::_setupCurrentState()
_calSaveCurrentValues();
_currentStickPositions.clear();
_currentStickPositions << state->stickPositions.leftX << state->stickPositions.leftY << state->stickPositions.rightX << state->stickPositions.rightY;
_currentGimbalPositions.clear();
_currentGimbalPositions << state->gimbalPositions.leftX << state->gimbalPositions.leftY << state->gimbalPositions.rightX << state->gimbalPositions.rightY;
emit stickPositionsChanged();
emit gimbalPositionsChanged();
emit nextEnabledChanged();
emit skipEnabledChanged();
}
@ -232,10 +177,6 @@ void JoystickConfigController::_axisValueChanged(int axis, int value) @@ -232,10 +177,6 @@ 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;
if(_axisCount > 4)
emit hasGimbalPitchChanged();
if(_axisCount > 5)
emit hasGimbalYawChanged();
}
}
if (_currentStep != -1) {
@ -619,11 +560,8 @@ void JoystickConfigController::_stopCalibration() @@ -619,11 +560,8 @@ void JoystickConfigController::_stopCalibration()
_setStatusText("");
emit calibratingChanged();
_currentStickPositions.clear();
_currentGimbalPositions.clear();
_currentStickPositions << _sticksCentered.leftX << _sticksCentered.leftY << _sticksCentered.rightX << _sticksCentered.rightY;
_currentGimbalPositions << stGimbalCentered.leftX << stGimbalCentered.leftY << stGimbalCentered.rightX << stGimbalCentered.rightY;
emit stickPositionsChanged();
emit gimbalPositionsChanged();
}
/// @brief Saves the current axis values, so that we can detect when the use moves an input.
@ -720,24 +658,6 @@ bool JoystickConfigController::throttleAxisReversed() @@ -720,24 +658,6 @@ bool JoystickConfigController::throttleAxisReversed()
}
}
bool JoystickConfigController::gimbalPitchAxisReversed()
{
if (_rgFunctionAxisMapping[Joystick::gimbalPitchFunction] != _axisNoAxis) {
return _rgAxisInfo[_rgFunctionAxisMapping[Joystick::gimbalPitchFunction]].reversed;
} else {
return false;
}
}
bool JoystickConfigController::gimbalYawAxisReversed()
{
if (_rgFunctionAxisMapping[Joystick::gimbalYawFunction] != _axisNoAxis) {
return _rgAxisInfo[_rgFunctionAxisMapping[Joystick::gimbalYawFunction]].reversed;
} else {
return false;
}
}
void JoystickConfigController::setTransmitterMode(int mode)
{
// Mode selection is disabled during calibration
@ -755,15 +675,11 @@ void JoystickConfigController::_signalAllAttitudeValueChanges() @@ -755,15 +675,11 @@ void JoystickConfigController::_signalAllAttitudeValueChanges()
emit pitchAxisMappedChanged(pitchAxisMapped());
emit yawAxisMappedChanged(yawAxisMapped());
emit throttleAxisMappedChanged(throttleAxisMapped());
emit gimbalPitchAxisMappedChanged(gimbalPitchAxisMapped());
emit gimbalYawAxisMappedChanged(gimbalYawAxisMapped());
emit rollAxisReversedChanged(rollAxisReversed());
emit pitchAxisReversedChanged(pitchAxisReversed());
emit yawAxisReversedChanged(yawAxisReversed());
emit throttleAxisReversedChanged(throttleAxisReversed());
emit gimbalPitchAxisReversedChanged(pitchAxisReversed());
emit gimbalYawAxisReversedChanged(yawAxisReversed());
emit transmitterModeChanged(_transmitterMode);
}
@ -781,8 +697,6 @@ void JoystickConfigController::_activeJoystickChanged(Joystick* joystick) @@ -781,8 +697,6 @@ void JoystickConfigController::_activeJoystickChanged(Joystick* joystick)
delete[] _axisRawValue;
_axisCount = 0;
_activeJoystick = nullptr;
emit hasGimbalPitchChanged();
emit hasGimbalYawChanged();
}
if (joystick) {
@ -797,8 +711,6 @@ void JoystickConfigController::_activeJoystickChanged(Joystick* joystick) @@ -797,8 +711,6 @@ void JoystickConfigController::_activeJoystickChanged(Joystick* joystick)
_axisRawValue = new int[_axisCount];
_setInternalCalibrationValuesFromSettings();
connect(_activeJoystick, &Joystick::rawAxisValueChanged, this, &JoystickConfigController::_axisValueChanged);
emit hasGimbalPitchChanged();
emit hasGimbalYawChanged();
}
}

27
src/VehicleSetup/JoystickConfigController.h

@ -46,20 +46,11 @@ public: @@ -46,20 +46,11 @@ public:
Q_PROPERTY(bool yawAxisMapped READ yawAxisMapped NOTIFY yawAxisMappedChanged)
Q_PROPERTY(bool throttleAxisMapped READ throttleAxisMapped NOTIFY throttleAxisMappedChanged)
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)
Q_PROPERTY(int rollAxisReversed READ rollAxisReversed NOTIFY rollAxisReversedChanged)
Q_PROPERTY(int pitchAxisReversed READ pitchAxisReversed NOTIFY pitchAxisReversedChanged)
Q_PROPERTY(int yawAxisReversed READ yawAxisReversed NOTIFY yawAxisReversedChanged)
Q_PROPERTY(int throttleAxisReversed READ throttleAxisReversed NOTIFY throttleAxisReversedChanged)
Q_PROPERTY(int gimbalPitchAxisReversed READ gimbalPitchAxisReversed NOTIFY gimbalPitchAxisReversedChanged)
Q_PROPERTY(int gimbalYawAxisReversed READ gimbalYawAxisReversed NOTIFY gimbalYawAxisReversedChanged)
Q_PROPERTY(bool deadbandToggle READ getDeadbandToggle WRITE setDeadbandToggle NOTIFY deadbandToggled)
Q_PROPERTY(int transmitterMode READ transmitterMode WRITE setTransmitterMode NOTIFY transmitterModeChanged)
@ -68,7 +59,6 @@ public: @@ -68,7 +59,6 @@ public:
Q_PROPERTY(bool skipEnabled READ skipEnabled NOTIFY skipEnabledChanged)
Q_PROPERTY(QList<qreal> stickPositions READ stickPositions NOTIFY stickPositionsChanged)
Q_PROPERTY(QList<qreal> gimbalPositions READ gimbalPositions NOTIFY gimbalPositionsChanged)
Q_INVOKABLE void cancelButtonClicked ();
Q_INVOKABLE void skipButtonClicked ();
@ -82,18 +72,11 @@ public: @@ -82,18 +72,11 @@ public:
bool pitchAxisMapped () { return _rgFunctionAxisMapping[Joystick::pitchFunction] != _axisNoAxis; }
bool yawAxisMapped () { return _rgFunctionAxisMapping[Joystick::yawFunction] != _axisNoAxis; }
bool throttleAxisMapped () { return _rgFunctionAxisMapping[Joystick::throttleFunction] != _axisNoAxis; }
bool gimbalPitchAxisMapped () { return _rgFunctionAxisMapping[Joystick::gimbalPitchFunction] != _axisNoAxis; }
bool gimbalYawAxisMapped () { return _rgFunctionAxisMapping[Joystick::gimbalYawFunction] != _axisNoAxis; }
bool rollAxisReversed ();
bool pitchAxisReversed ();
bool yawAxisReversed ();
bool throttleAxisReversed ();
bool gimbalPitchAxisReversed ();
bool gimbalYawAxisReversed ();
bool hasGimbalPitch () { return _axisCount > 4; }
bool hasGimbalYaw () { return _axisCount > 5; }
bool getDeadbandToggle ();
void setDeadbandToggle (bool);
@ -108,7 +91,6 @@ public: @@ -108,7 +91,6 @@ public:
bool skipEnabled ();
QList<qreal> stickPositions () { return _currentStickPositions; }
QList<qreal> gimbalPositions () { return _currentGimbalPositions; }
struct stateStickPositions {
qreal leftX;
@ -124,23 +106,16 @@ signals: @@ -124,23 +106,16 @@ signals:
void pitchAxisMappedChanged (bool mapped);
void yawAxisMappedChanged (bool mapped);
void throttleAxisMappedChanged (bool mapped);
void gimbalPitchAxisMappedChanged (bool mapped);
void gimbalYawAxisMappedChanged (bool mapped);
void rollAxisReversedChanged (bool reversed);
void pitchAxisReversedChanged (bool reversed);
void yawAxisReversedChanged (bool reversed);
void throttleAxisReversedChanged (bool reversed);
void gimbalPitchAxisReversedChanged (bool reversed);
void gimbalYawAxisReversedChanged (bool reversed);
void deadbandToggled (bool value);
void transmitterModeChanged (int mode);
void calibratingChanged ();
void nextEnabledChanged ();
void skipEnabledChanged ();
void stickPositionsChanged ();
void gimbalPositionsChanged ();
void hasGimbalPitchChanged ();
void hasGimbalYawChanged ();
void statusTextChanged ();
// @brief Signalled when in unit test mode and a message box should be displayed by the next button
@ -170,7 +145,6 @@ private: @@ -170,7 +145,6 @@ private:
Joystick::AxisFunction_t function;
const char* instructions;
stateStickPositions stickPositions;
stateStickPositions gimbalPositions;
inputFn rcInputFn;
buttonFn nextFn;
buttonFn skipFn;
@ -239,7 +213,6 @@ private: @@ -239,7 +213,6 @@ private:
stateStickPositions _sticksPitchDown;
QList<qreal> _currentStickPositions;
QList<qreal> _currentGimbalPositions;
int _rgFunctionAxisMapping[Joystick::maxFunction]; ///< Maps from joystick function to axis index. _axisMax indicates axis not set for this function.

38
src/VehicleSetup/JoystickConfigGeneral.qml

@ -207,44 +207,6 @@ Item { @@ -207,44 +207,6 @@ Item {
throttleAxis.axisValue = _activeJoystick.negativeThrust ? throttle * -32768.0 : (-2 * throttle + 1) * 32768.0
}
}
QGCLabel {
id: gimbalPitchLabel
width: _attitudeLabelWidth
text: qsTr("Gimbal Pitch")
visible: controller.hasGimbalPitch && _activeJoystick.gimbalEnabled
}
AxisMonitor {
id: gimbalPitchAxis
height: ScreenTools.defaultFontPixelHeight
width: axisMonitorWidth
mapped: controller.gimbalPitchAxisMapped
reversed: controller.gimbalPitchAxisReversed
visible: controller.hasGimbalPitch && _activeJoystick.gimbalEnabled
}
QGCLabel {
id: gimbalYawLabel
width: _attitudeLabelWidth
text: qsTr("Gimbal Yaw")
visible: controller.hasGimbalYaw && _activeJoystick.gimbalEnabled
}
AxisMonitor {
id: gimbalYawAxis
height: ScreenTools.defaultFontPixelHeight
width: axisMonitorWidth
mapped: controller.gimbalYawAxisMapped
reversed: controller.gimbalYawAxisReversed
visible: controller.hasGimbalYaw && _activeJoystick.gimbalEnabled
}
Connections {
target: _activeJoystick
onManualControlGimbal: {
gimbalPitchAxis.axisValue = gimbalPitch * 32768.0
gimbalYawAxis.axisValue = gimbalYaw * 32768.0
}
}
}
}
Rectangle {

Loading…
Cancel
Save