Browse Source

Calibration of gimbal axis done.

QGC4.4
Gus Grubba 6 years ago
parent
commit
85468e6b0f
  1. 67
      src/Joystick/Joystick.cc
  2. 1565
      src/VehicleSetup/JoystickConfig.qml
  3. 246
      src/VehicleSetup/JoystickConfigController.cc
  4. 75
      src/VehicleSetup/JoystickConfigController.h

67
src/Joystick/Joystick.cc

@ -175,10 +175,8 @@ void Joystick::_activeVehicleChanged(Vehicle* activeVehicle) @@ -175,10 +175,8 @@ void Joystick::_activeVehicleChanged(Vehicle* activeVehicle)
void Joystick::_loadSettings()
{
QSettings settings;
QSettings settings;
settings.beginGroup(_settingsGroup);
Vehicle* activeVehicle = _multiVehicleManager->activeVehicle();
if(_txModeSettingsKey && activeVehicle)
@ -191,25 +189,25 @@ void Joystick::_loadSettings() @@ -191,25 +189,25 @@ void Joystick::_loadSettings()
qCDebug(JoystickLog) << "_loadSettings " << _name;
_calibrated = settings.value(_calibratedSettingsKey, false).toBool();
_exponential = settings.value(_exponentialSettingsKey, 0).toFloat();
_accumulator = settings.value(_accumulatorSettingsKey, false).toBool();
_deadband = settings.value(_deadbandSettingsKey, false).toBool();
_calibrated = settings.value(_calibratedSettingsKey, false).toBool();
_exponential = settings.value(_exponentialSettingsKey, 0).toFloat();
_accumulator = settings.value(_accumulatorSettingsKey, false).toBool();
_deadband = settings.value(_deadbandSettingsKey, false).toBool();
_frequency = settings.value(_frequencySettingsKey, 25.0f).toFloat();
_circleCorrection = settings.value(_circleCorrectionSettingsKey, false).toBool();
_frequency = settings.value(_frequencySettingsKey, 25.0f).toFloat();
_throttleMode = (ThrottleMode_t)settings.value(_throttleModeSettingsKey, ThrottleModeDownZero).toInt(&convertOk);
_throttleMode = static_cast<ThrottleMode_t>(settings.value(_throttleModeSettingsKey, ThrottleModeDownZero).toInt(&convertOk));
badSettings |= !convertOk;
qCDebug(JoystickLog) << "_loadSettings calibrated:txmode:throttlemode:exponential:deadband:badsettings" << _calibrated << _transmitterMode << _throttleMode << _exponential << _deadband << badSettings;
QString minTpl ("Axis%1Min");
QString maxTpl ("Axis%1Max");
QString trimTpl ("Axis%1Trim");
QString revTpl ("Axis%1Rev");
QString minTpl ("Axis%1Min");
QString maxTpl ("Axis%1Max");
QString trimTpl ("Axis%1Trim");
QString revTpl ("Axis%1Rev");
QString deadbndTpl ("Axis%1Deadbnd");
for (int axis=0; axis<_axisCount; axis++) {
for (int axis = 0; axis < _axisCount; axis++) {
Calibration_t* calibration = &_rgCalibration[axis];
calibration->center = settings.value(trimTpl.arg(axis), 0).toInt(&convertOk);
@ -226,7 +224,6 @@ void Joystick::_loadSettings() @@ -226,7 +224,6 @@ void Joystick::_loadSettings()
calibration->reversed = settings.value(revTpl.arg(axis), false).toBool();
qCDebug(JoystickLog) << "_loadSettings axis:min:max:trim:reversed:deadband:badsettings" << axis << calibration->min << calibration->max << calibration->center << calibration->reversed << calibration->deadband << badSettings;
}
@ -268,31 +265,29 @@ void Joystick::_saveSettings() @@ -268,31 +265,29 @@ void Joystick::_saveSettings()
settings.beginGroup(_name);
settings.setValue(_calibratedSettingsKey, _calibrated);
settings.setValue(_exponentialSettingsKey, _exponential);
settings.setValue(_accumulatorSettingsKey, _accumulator);
settings.setValue(_deadbandSettingsKey, _deadband);
settings.setValue(_circleCorrectionSettingsKey, _circleCorrection);
settings.setValue(_frequencySettingsKey, _frequency);
settings.setValue(_calibratedSettingsKey, _calibrated);
settings.setValue(_exponentialSettingsKey, _exponential);
settings.setValue(_accumulatorSettingsKey, _accumulator);
settings.setValue(_deadbandSettingsKey, _deadband);
settings.setValue(_frequencySettingsKey, _frequency);
settings.setValue(_throttleModeSettingsKey, _throttleMode);
settings.setValue(_circleCorrectionSettingsKey, _circleCorrection);
qCDebug(JoystickLog) << "_saveSettings calibrated:throttlemode:deadband:txmode" << _calibrated << _throttleMode << _deadband << _circleCorrection << _transmitterMode;
QString minTpl ("Axis%1Min");
QString maxTpl ("Axis%1Max");
QString trimTpl ("Axis%1Trim");
QString revTpl ("Axis%1Rev");
QString minTpl ("Axis%1Min");
QString maxTpl ("Axis%1Max");
QString trimTpl ("Axis%1Trim");
QString revTpl ("Axis%1Rev");
QString deadbndTpl ("Axis%1Deadbnd");
for (int axis=0; axis<_axisCount; axis++) {
for (int axis = 0; axis < _axisCount; axis++) {
Calibration_t* calibration = &_rgCalibration[axis];
settings.setValue(trimTpl.arg(axis), calibration->center);
settings.setValue(minTpl.arg(axis), calibration->min);
settings.setValue(maxTpl.arg(axis), calibration->max);
settings.setValue(revTpl.arg(axis), calibration->reversed);
settings.setValue(deadbndTpl.arg(axis), calibration->deadband);
qCDebug(JoystickLog) << "_saveSettings name:axis:min:max:trim:reversed:deadband"
<< _name
<< axis
@ -308,12 +303,12 @@ void Joystick::_saveSettings() @@ -308,12 +303,12 @@ void Joystick::_saveSettings()
int temp[maxFunction];
_remapAxes(_transmitterMode, 2, temp);
for (int function=0; function<maxFunction; function++) {
for (int function = 0; function < maxFunction; function++) {
settings.setValue(_rgFunctionSettingsKey[function], temp[function]);
qCDebug(JoystickLog) << "_saveSettings name:function:axis" << _name << function << _rgFunctionSettingsKey[function];
}
for (int button=0; button<_totalButtonCount; button++) {
for (int button = 0; button < _totalButtonCount; button++) {
settings.setValue(QString(_buttonActionSettingsKey).arg(button), _rgButtonActions[button]);
qCDebug(JoystickLog) << "_saveSettings button:action" << button << _rgButtonActions[button];
}
@ -321,13 +316,11 @@ void Joystick::_saveSettings() @@ -321,13 +316,11 @@ void Joystick::_saveSettings()
// Relative mappings of axis functions between different TX modes
int Joystick::_mapFunctionMode(int mode, int function) {
static const int mapping[][4] = {
{ 2, 1, 0, 3 },
{ 2, 3, 0, 1 },
{ 0, 1, 2, 3 },
{ 0, 3, 2, 1 }};
static const int mapping[][6] = {
{ yawFunction, pitchFunction, rollFunction, throttleFunction, gimbalPitchFunction, gimbalYawFunction },
{ yawFunction, throttleFunction, rollFunction, pitchFunction, gimbalPitchFunction, gimbalYawFunction },
{ rollFunction, pitchFunction, yawFunction, throttleFunction, gimbalPitchFunction, gimbalYawFunction },
{ rollFunction, throttleFunction, yawFunction, pitchFunction, gimbalPitchFunction, gimbalYawFunction }};
return mapping[mode-1][function];
}

1565
src/VehicleSetup/JoystickConfig.qml

File diff suppressed because it is too large Load Diff

246
src/VehicleSetup/JoystickConfigController.cc

@ -43,13 +43,74 @@ const char* JoystickConfigController::_imageRollRight = "joystickRollRight.p @@ -43,13 +43,74 @@ const char* JoystickConfigController::_imageRollRight = "joystickRollRight.p
const char* JoystickConfigController::_imagePitchUp = "joystickPitchUp.png";
const char* JoystickConfigController::_imagePitchDown = "joystickPitchDown.png";
static const JoystickConfigController::stateStickPositions stSticksCentered {
0.25, 0.5, 0.75, 0.5
};
static const JoystickConfigController::stateStickPositions stLeftStickUp {
0.25, 0.3084, 0.75, 0.5
};
static const JoystickConfigController::stateStickPositions stLeftStickDown {
0.25, 0.6916, 0.75, 0.5
};
static const JoystickConfigController::stateStickPositions stLeftStickLeft {
0.1542, 0.5, 0.75, 0.5
};
static const JoystickConfigController::stateStickPositions stLeftStickRight {
0.3458, 0.5, 0.75, 0.5
};
static const JoystickConfigController::stateStickPositions stRightStickUp {
0.25, 0.5, 0.75, 0.3084
};
static const JoystickConfigController::stateStickPositions stRightStickDown {
0.25, 0.5, 0.75, 0.6916
};
static const JoystickConfigController::stateStickPositions stRightStickLeft {
0.25, 0.5, 0.6542, 0.5
};
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
};
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
};
JoystickConfigController::JoystickConfigController(void)
: _joystickManager(qgcApp()->toolbox()->joystickManager())
{
connect(_joystickManager, &JoystickManager::activeJoystickChanged, this, &JoystickConfigController::_activeJoystickChanged);
_activeJoystickChanged(_joystickManager->activeJoystick());
_setStickPositions();
_resetInternalCalibrationValues();
_currentStickPositions << _sticksCentered.leftX << _sticksCentered.leftY << _sticksCentered.rightX << _sticksCentered.rightY;
_currentGimbalPositions << stGimbalCentered.leftX << stGimbalCentered.leftY << stGimbalCentered.rightX << stGimbalCentered.rightY;
}
void JoystickConfigController::start(void)
@ -91,29 +152,29 @@ const JoystickConfigController::stateMachineEntry* JoystickConfigController::_ge @@ -91,29 +152,29 @@ const JoystickConfigController::stateMachineEntry* JoystickConfigController::_ge
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...";
static const char* msgComplete = "All settings have been captured. Click Next to enable the joystick.";
static const stateMachineEntry rgStateMachine[] = {
//Function
{ Joystick::maxFunction, msgBegin, _imageCenter, &JoystickConfigController::_inputCenterWaitBegin, &JoystickConfigController::_saveAllTrims, nullptr, 0 },
{ Joystick::throttleFunction, msgThrottleUp, _imageThrottleUp, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 0 },
{ Joystick::throttleFunction, msgThrottleDown, _imageThrottleDown, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 0 },
{ Joystick::yawFunction, msgYawRight, _imageYawRight, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 1 },
{ Joystick::yawFunction, msgYawLeft, _imageYawLeft, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 1 },
{ Joystick::rollFunction, msgRollRight, _imageRollRight, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 2 },
{ Joystick::rollFunction, msgRollLeft, _imageRollLeft, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 2 },
{ Joystick::pitchFunction, msgPitchUp, _imagePitchUp, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 3 },
{ Joystick::pitchFunction, msgPitchDown, _imagePitchDown, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 3 },
{ Joystick::pitchFunction, msgPitchCenter, _imageCenter, &JoystickConfigController::_inputCenterWait, nullptr, nullptr, 3 },
{ Joystick::gimbalPitchFunction, msgGimbalPitchUp, _imageThrottleUp, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 4 },
{ Joystick::gimbalPitchFunction, msgGimbalPitchDown, _imageThrottleDown, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 4 },
{ Joystick::gimbalYawFunction, msgGimbalYawRight, _imageYawRight, &JoystickConfigController::_inputStickDetect, nullptr, nullptr, 5 },
{ Joystick::gimbalYawFunction, msgGimbalYawLeft, _imageYawLeft, &JoystickConfigController::_inputStickMin, nullptr, nullptr, 5 },
{ Joystick::maxFunction, msgComplete, _imageCenter, nullptr, &JoystickConfigController::_writeCalibration, nullptr, -1 },
{ 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 },
{ 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 },
{ Joystick::maxFunction, msgComplete, _sticksCentered, stGimbalCentered, nullptr, &JoystickConfigController::_writeCalibration, nullptr, -1 },
};
Q_ASSERT(step >=0 && step < static_cast<int>((sizeof(rgStateMachine) / sizeof(rgStateMachine[0]))));
Q_ASSERT(step >= 0 && step < static_cast<int>((sizeof(rgStateMachine) / sizeof(rgStateMachine[0]))));
return &rgStateMachine[step];
}
@ -132,13 +193,18 @@ void JoystickConfigController::_advanceState() @@ -132,13 +193,18 @@ void JoystickConfigController::_advanceState()
void JoystickConfigController::_setupCurrentState()
{
const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
_statusText->setProperty("text", state->instructions);
_setHelpImage(state->image);
_setStatusText(state->instructions);
_stickDetectAxis = _axisNoAxis;
_stickDetectSettleStarted = false;
_calSaveCurrentValues();
_nextButton->setEnabled(state->nextFn != nullptr);
_skipButton->setEnabled(state->skipFn != nullptr);
_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();
}
void JoystickConfigController::_axisValueChanged(int axis, int value)
@ -151,6 +217,7 @@ void JoystickConfigController::_axisValueChanged(int axis, int value) @@ -151,6 +217,7 @@ 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 (_currentStep != -1) {
@ -404,7 +471,6 @@ void JoystickConfigController::_resetInternalCalibrationValues() @@ -404,7 +471,6 @@ void JoystickConfigController::_resetInternalCalibrationValues()
info->axisMax = JoystickConfigController::_calCenterPoint;
info->axisTrim = JoystickConfigController::_calCenterPoint;
}
// Initialize attitude function mapping to function axis not set
for (size_t i = 0; i < Joystick::maxFunction; i++) {
_rgFunctionAxisMapping[i] = _axisNoAxis;
@ -456,40 +522,32 @@ void JoystickConfigController::_validateCalibration() @@ -456,40 +522,32 @@ void JoystickConfigController::_validateCalibration()
{
for (int chan = 0; chan < _axisCount; chan++) {
struct AxisInfo* info = &_rgAxisInfo[chan];
if (chan < _axisCount) {
// Validate Min/Max values. Although the axis appears as available we still may
// not have good min/max/trim values for it. Set to defaults if needed.
if (info->axisMin < _calValidMinValue || info->axisMax > _calValidMaxValue) {
qCDebug(JoystickConfigControllerLog) << "_validateCalibration resetting axis" << chan;
info->axisMin = _calDefaultMinValue;
info->axisMax = _calDefaultMaxValue;
info->axisTrim = info->axisMin + ((info->axisMax - info->axisMin) / 2);
}
switch (_rgAxisInfo[chan].function) {
case Joystick::throttleFunction:
case Joystick::yawFunction:
case Joystick::rollFunction:
case Joystick::pitchFunction:
// Make sure trim is within min/max
if (info->axisTrim < info->axisMin) {
info->axisTrim = info->axisMin;
} else if (info->axisTrim > info->axisMax) {
info->axisTrim = info->axisMax;
}
break;
default:
// Non-attitude control axis have calculated trim
info->axisTrim = info->axisMin + ((info->axisMax - info->axisMin) / 2);
break;
}
} else {
// Unavailable axiss are set to defaults
qCDebug(JoystickConfigControllerLog) << "_validateCalibration resetting unavailable axis" << chan;
// Validate Min/Max values. Although the axis appears as available we still may
// not have good min/max/trim values for it. Set to defaults if needed.
if (info->axisMin < _calValidMinValue || info->axisMax > _calValidMaxValue) {
qCDebug(JoystickConfigControllerLog) << "_validateCalibration resetting axis" << chan;
info->axisMin = _calDefaultMinValue;
info->axisMax = _calDefaultMaxValue;
info->axisTrim = info->axisMin + ((info->axisMax - info->axisMin) / 2);
info->deadband = 0;
info->reversed = false;
}
switch (_rgAxisInfo[chan].function) {
case Joystick::throttleFunction:
case Joystick::yawFunction:
case Joystick::rollFunction:
case Joystick::pitchFunction:
case Joystick::gimbalPitchFunction:
case Joystick::gimbalYawFunction:
// Make sure trim is within min/max
if (info->axisTrim < info->axisMin) {
info->axisTrim = info->axisMin;
} else if (info->axisTrim > info->axisMax) {
info->axisTrim = info->axisMax;
}
break;
default:
// Non-attitude control axis have calculated trim
info->axisTrim = info->axisMin + ((info->axisMax - info->axisMin) / 2);
break;
}
}
}
@ -543,12 +601,11 @@ void JoystickConfigController::_stopCalibration() @@ -543,12 +601,11 @@ void JoystickConfigController::_stopCalibration()
_currentStep = -1;
_activeJoystick->setCalibrationMode(false);
_setInternalCalibrationValuesFromSettings();
_statusText->setProperty("text", "");
_setStatusText("");
_nextButton->setProperty("text", tr("Calibrate"));
_nextButton->setEnabled(true);
_cancelButton->setEnabled(false);
_skipButton->setEnabled(false);
_setHelpImage(_imageCenter);
emit calibratingChanged();
}
@ -565,47 +622,65 @@ void JoystickConfigController::_calSaveCurrentValues() @@ -565,47 +622,65 @@ void JoystickConfigController::_calSaveCurrentValues()
void JoystickConfigController::_calSave()
{
_calState = calStateSave;
_statusText->setProperty("text",
tr("The current calibration settings are now displayed for each axis on screen.\n\n"
"Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values."));
_setStatusText(tr(
"The current calibration settings are now displayed for each axis on screen.\n\n"
"Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values."));
_nextButton->setEnabled(true);
_skipButton->setEnabled(false);
_cancelButton->setEnabled(true);
// This updates the internal values according to the validation rules. Then _updateView will tick and update ui
// such that the settings that will be written our are displayed.
// such that the settings that will be written out are displayed.
_validateCalibration();
}
void JoystickConfigController::_setHelpImage(const char* imageFile)
void JoystickConfigController::_setStickPositions()
{
QString file = _imageFilePrefix;
_sticksCentered = stSticksCentered;
switch(_transmitterMode) {
case 1:
file += _imageFileMode1Dir;
_sticksThrottleUp = stRightStickUp;
_sticksThrottleDown = stRightStickDown;
_sticksYawLeft = stLeftStickLeft;
_sticksYawRight = stLeftStickRight;
_sticksRollLeft = stRightStickLeft;
_sticksRollRight = stRightStickRight;
_sticksPitchUp = stLeftStickDown;
_sticksPitchDown = stLeftStickUp;
break;
case 2:
file += _imageFileMode2Dir;
_sticksThrottleUp = stLeftStickUp;
_sticksThrottleDown = stLeftStickDown;
_sticksYawLeft = stLeftStickLeft;
_sticksYawRight = stLeftStickRight;
_sticksRollLeft = stRightStickLeft;
_sticksRollRight = stRightStickRight;
_sticksPitchUp = stRightStickDown;
_sticksPitchDown = stRightStickUp;
break;
case 3:
file += _imageFileMode3Dir;
_sticksThrottleUp = stRightStickUp;
_sticksThrottleDown = stRightStickDown;
_sticksYawLeft = stRightStickLeft;
_sticksYawRight = stRightStickRight;
_sticksRollLeft = stLeftStickLeft;
_sticksRollRight = stLeftStickRight;
_sticksPitchUp = stLeftStickDown;
_sticksPitchDown = stLeftStickUp;
break;
case 4:
file += _imageFileMode4Dir;
_sticksThrottleUp = stLeftStickUp;
_sticksThrottleDown = stLeftStickDown;
_sticksYawLeft = stRightStickLeft;
_sticksYawRight = stRightStickRight;
_sticksRollLeft = stLeftStickLeft;
_sticksRollRight = stLeftStickRight;
_sticksPitchUp = stRightStickDown;
_sticksPitchDown = stRightStickUp;
break;
default:
Q_ASSERT(false);
}
file += imageFile;
qCDebug(JoystickConfigControllerLog) << "_setHelpImage" << file;
_imageHelp = file;
emit imageHelpChanged(file);
}
bool JoystickConfigController::rollAxisReversed()
@ -664,15 +739,12 @@ bool JoystickConfigController::gimbalYawAxisReversed() @@ -664,15 +739,12 @@ bool JoystickConfigController::gimbalYawAxisReversed()
void JoystickConfigController::setTransmitterMode(int mode)
{
if (mode > 0 && mode <= 4) {
// Mode selection is disabled during calibration
if (mode > 0 && mode <= 4 && _currentStep == -1) {
_transmitterMode = mode;
if (_currentStep != -1) { // This should never be true, mode selection is disabled during calibration
const stateMachineEntry* state = _getStateMachineEntry(_currentStep);
_setHelpImage(state->image);
} else {
_activeJoystick->setTXMode(mode);
_setInternalCalibrationValuesFromSettings();
}
_setStickPositions();
_activeJoystick->setTXMode(mode);
_setInternalCalibrationValuesFromSettings();
}
}
@ -708,6 +780,7 @@ void JoystickConfigController::_activeJoystickChanged(Joystick* joystick) @@ -708,6 +780,7 @@ void JoystickConfigController::_activeJoystickChanged(Joystick* joystick)
delete[] _axisRawValue;
_axisCount = 0;
_activeJoystick = nullptr;
emit hasGimbalChanged();
}
if (joystick) {
@ -722,6 +795,7 @@ void JoystickConfigController::_activeJoystickChanged(Joystick* joystick) @@ -722,6 +795,7 @@ void JoystickConfigController::_activeJoystickChanged(Joystick* joystick)
_axisRawValue = new int[_axisCount];
_setInternalCalibrationValuesFromSettings();
connect(_activeJoystick, &Joystick::rawAxisValueChanged, this, &JoystickConfigController::_axisValueChanged);
emit hasGimbalChanged();
}
}
@ -729,3 +803,9 @@ bool JoystickConfigController::_validAxis(int axis) @@ -729,3 +803,9 @@ bool JoystickConfigController::_validAxis(int axis)
{
return axis >= 0 && axis < _axisCount;
}
void JoystickConfigController::_setStatusText(const QString& text)
{
_statusText = text;
emit statusTextChanged();
}

75
src/VehicleSetup/JoystickConfigController.h

@ -7,10 +7,8 @@ @@ -7,10 +7,8 @@
*
****************************************************************************/
/// @file
/// @brief Radio Config Qml Controller
/// @brief Joystick Config Qml Controller
/// @author Don Gagne <don@thegagnes.com
#ifndef JoystickConfigController_H
@ -31,7 +29,6 @@ namespace Ui { @@ -31,7 +29,6 @@ namespace Ui {
class JoystickConfigController;
}
class JoystickConfigController : public FactPanelController
{
Q_OBJECT
@ -42,7 +39,8 @@ public: @@ -42,7 +39,8 @@ public:
JoystickConfigController(void);
~JoystickConfigController();
Q_PROPERTY(QQuickItem* statusText MEMBER _statusText)
Q_PROPERTY(QString statusText READ statusText NOTIFY statusTextChanged)
Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton)
Q_PROPERTY(QQuickItem* nextButton MEMBER _nextButton)
Q_PROPERTY(QQuickItem* skipButton MEMBER _skipButton)
@ -52,6 +50,7 @@ public: @@ -52,6 +50,7 @@ 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 gimbalPitchAxisMapped READ gimbalPitchAxisMapped NOTIFY gimbalPitchAxisMappedChanged)
Q_PROPERTY(bool gimbalYawAxisMapped READ gimbalYawAxisMapped NOTIFY gimbalYawAxisMappedChanged)
@ -65,16 +64,20 @@ public: @@ -65,16 +64,20 @@ public:
Q_PROPERTY(bool deadbandToggle READ getDeadbandToggle WRITE setDeadbandToggle NOTIFY deadbandToggled)
Q_PROPERTY(int transmitterMode READ transmitterMode WRITE setTransmitterMode NOTIFY transmitterModeChanged)
Q_PROPERTY(QString imageHelp MEMBER _imageHelp NOTIFY imageHelpChanged)
Q_PROPERTY(bool calibrating READ calibrating NOTIFY calibratingChanged)
Q_PROPERTY(int transmitterMode READ transmitterMode WRITE setTransmitterMode NOTIFY transmitterModeChanged)
Q_PROPERTY(bool calibrating READ calibrating NOTIFY calibratingChanged)
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 ();
Q_INVOKABLE void nextButtonClicked ();
Q_INVOKABLE void start ();
Q_INVOKABLE void setDeadbandValue (int axis, int value);
QString statusText () { return _statusText; }
bool rollAxisMapped () { return _rgFunctionAxisMapping[Joystick::rollFunction] != _axisNoAxis; }
bool pitchAxisMapped () { return _rgFunctionAxisMapping[Joystick::pitchFunction] != _axisNoAxis; }
bool yawAxisMapped () { return _rgFunctionAxisMapping[Joystick::yawFunction] != _axisNoAxis; }
@ -89,6 +92,8 @@ public: @@ -89,6 +92,8 @@ public:
bool gimbalPitchAxisReversed ();
bool gimbalYawAxisReversed ();
bool hasGimbal () { return _axisCount > 5; }
bool getDeadbandToggle ();
void setDeadbandToggle (bool);
@ -98,31 +103,40 @@ public: @@ -98,31 +103,40 @@ public:
void setTransmitterMode (int mode);
bool calibrating () { return _currentStep != -1; }
QList<qreal> stickPositions () { return _currentStickPositions; }
QList<qreal> gimbalPositions () { return _currentGimbalPositions; }
struct stateStickPositions {
qreal leftX;
qreal leftY;
qreal rightX;
qreal rightY;
};
signals:
void axisValueChanged (int axis, int value);
void axisDeadbandChanged (int axis, int value);
void rollAxisMappedChanged (bool mapped);
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 imageHelpChanged (QString source);
void transmitterModeChanged (int mode);
void calibratingChanged ();
void stickPositionsChanged ();
void gimbalPositionsChanged ();
void hasGimbalChanged ();
void statusTextChanged ();
// @brief Signalled when in unit test mode and a message box should be displayed by the next button
void nextButtonMessageBoxDisplayed ();
@ -143,13 +157,14 @@ private: @@ -143,13 +157,14 @@ private:
calStateTrims,
calStateSave
};
typedef void (JoystickConfigController::*inputFn)(Joystick::AxisFunction_t function, int axis, int value);
typedef void (JoystickConfigController::*buttonFn)(void);
struct stateMachineEntry {
Joystick::AxisFunction_t function;
const char* instructions;
const char* image;
stateStickPositions stickPositions;
stateStickPositions gimbalPositions;
inputFn rcInputFn;
buttonFn nextFn;
buttonFn skipFn;
@ -202,9 +217,11 @@ private: @@ -202,9 +217,11 @@ private:
void _calSaveCurrentValues ();
void _setHelpImage(const char* imageFile);
void _setStickPositions ();
void _signalAllAttitudeValueChanges();
void _setStatusText (const QString& text);
// Member variables
@ -222,7 +239,20 @@ private: @@ -222,7 +239,20 @@ private:
static const char* _imageRollRight;
static const char* _imagePitchUp;
static const char* _imagePitchDown;
stateStickPositions _sticksCentered;
stateStickPositions _sticksThrottleUp;
stateStickPositions _sticksThrottleDown;
stateStickPositions _sticksYawLeft;
stateStickPositions _sticksYawRight;
stateStickPositions _sticksRollLeft;
stateStickPositions _sticksRollRight;
stateStickPositions _sticksPitchUp;
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.
static const int _attitudeControls = 5;
@ -258,13 +288,12 @@ private: @@ -258,13 +288,12 @@ private:
QTime _stickDetectSettleElapsed;
static const int _stickDetectSettleMSecs;
QQuickItem* _statusText = nullptr;
QString _statusText;
QQuickItem* _cancelButton = nullptr;
QQuickItem* _nextButton = nullptr;
QQuickItem* _skipButton = nullptr;
QString _imageHelp;
JoystickManager* _joystickManager;
};

Loading…
Cancel
Save