Commit 6d9fb038 authored by Gregory Dymarek's avatar Gregory Dymarek

Cleanup & Sync

parent 8c1cbc6d
...@@ -24,6 +24,7 @@ const char* Joystick::_buttonActionSettingsKey = "ButtonActionName%1"; ...@@ -24,6 +24,7 @@ const char* Joystick::_buttonActionSettingsKey = "ButtonActionName%1";
const char* Joystick::_throttleModeSettingsKey = "ThrottleMode"; const char* Joystick::_throttleModeSettingsKey = "ThrottleMode";
const char* Joystick::_exponentialSettingsKey = "Exponential"; const char* Joystick::_exponentialSettingsKey = "Exponential";
const char* Joystick::_accumulatorSettingsKey = "Accumulator"; const char* Joystick::_accumulatorSettingsKey = "Accumulator";
const char* Joystick::_deadbandSettingsKey = "Deadband";
const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = { const char* Joystick::_rgFunctionSettingsKey[Joystick::maxFunction] = {
"RollAxis", "RollAxis",
...@@ -48,6 +49,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC ...@@ -48,6 +49,7 @@ Joystick::Joystick(const QString& name, int axisCount, int buttonCount, int hatC
, _throttleMode(ThrottleModeCenterZero) , _throttleMode(ThrottleModeCenterZero)
, _exponential(false) , _exponential(false)
, _accumulator(false) , _accumulator(false)
, _deadband(false)
, _activeVehicle(NULL) , _activeVehicle(NULL)
, _pollingStartedForCalibration(false) , _pollingStartedForCalibration(false)
, _multiVehicleManager(multiVehicleManager) , _multiVehicleManager(multiVehicleManager)
...@@ -89,6 +91,7 @@ void Joystick::_loadSettings(void) ...@@ -89,6 +91,7 @@ void Joystick::_loadSettings(void)
_calibrated = settings.value(_calibratedSettingsKey, false).toBool(); _calibrated = settings.value(_calibratedSettingsKey, false).toBool();
_exponential = settings.value(_exponentialSettingsKey, false).toBool(); _exponential = settings.value(_exponentialSettingsKey, false).toBool();
_accumulator = settings.value(_accumulatorSettingsKey, false).toBool(); _accumulator = settings.value(_accumulatorSettingsKey, false).toBool();
_deadband = settings.value(_deadbandSettingsKey, false).toBool();
_throttleMode = (ThrottleMode_t)settings.value(_throttleModeSettingsKey, ThrottleModeCenterZero).toInt(&convertOk); _throttleMode = (ThrottleMode_t)settings.value(_throttleModeSettingsKey, ThrottleModeCenterZero).toInt(&convertOk);
badSettings |= !convertOk; badSettings |= !convertOk;
...@@ -154,6 +157,7 @@ void Joystick::_saveSettings(void) ...@@ -154,6 +157,7 @@ void Joystick::_saveSettings(void)
settings.setValue(_calibratedSettingsKey, _calibrated); settings.setValue(_calibratedSettingsKey, _calibrated);
settings.setValue(_exponentialSettingsKey, _exponential); settings.setValue(_exponentialSettingsKey, _exponential);
settings.setValue(_accumulatorSettingsKey, _accumulator); settings.setValue(_accumulatorSettingsKey, _accumulator);
settings.setValue(_deadbandSettingsKey, _deadband);
settings.setValue(_throttleModeSettingsKey, _throttleMode); settings.setValue(_throttleModeSettingsKey, _throttleMode);
qCDebug(JoystickLog) << "_saveSettings calibrated:throttlemode" << _calibrated << _throttleMode; qCDebug(JoystickLog) << "_saveSettings calibrated:throttlemode" << _calibrated << _throttleMode;
...@@ -213,10 +217,9 @@ float Joystick::_adjustRange(int value, Calibration_t calibration) ...@@ -213,10 +217,9 @@ float Joystick::_adjustRange(int value, Calibration_t calibration)
axisLength = calibration.center - calibration.min; axisLength = calibration.center - calibration.min;
} }
if (_accumulator) {//deadband will be applied only in accumulator mode if (_deadband) {
int deadband = calibration.deadband*1.5; //we are increasing deadband to accommodate slight variations if (valueNormalized>calibration.deadband) valueNormalized-=calibration.deadband;
if (valueNormalized>deadband) valueNormalized-=deadband; else if (valueNormalized<-calibration.deadband) valueNormalized+=calibration.deadband;
else if (valueNormalized<-deadband) valueNormalized+=deadband;
else valueNormalized = 0.f; else valueNormalized = 0.f;
} }
...@@ -572,6 +575,19 @@ void Joystick::setAccumulator(bool accu) ...@@ -572,6 +575,19 @@ void Joystick::setAccumulator(bool accu)
emit accumulatorChanged(_accumulator); emit accumulatorChanged(_accumulator);
} }
bool Joystick::deadband(void)
{
return _deadband;
}
void Joystick::setDeadband(bool deadband)
{
_deadband = deadband;
_saveSettings();
emit deadbandChanged(_deadband);
}
void Joystick::startCalibrationMode(CalibrationMode_t mode) void Joystick::startCalibrationMode(CalibrationMode_t mode)
{ {
if (mode == CalibrationModeOff) { if (mode == CalibrationModeOff) {
......
...@@ -68,6 +68,7 @@ public: ...@@ -68,6 +68,7 @@ public:
Q_PROPERTY(int throttleMode READ throttleMode WRITE setThrottleMode NOTIFY throttleModeChanged) Q_PROPERTY(int throttleMode READ throttleMode WRITE setThrottleMode NOTIFY throttleModeChanged)
Q_PROPERTY(int exponential READ exponential WRITE setExponential NOTIFY exponentialChanged) Q_PROPERTY(int exponential READ exponential WRITE setExponential NOTIFY exponentialChanged)
Q_PROPERTY(int accumulator READ accumulator WRITE setAccumulator NOTIFY accumulatorChanged) Q_PROPERTY(int accumulator READ accumulator WRITE setAccumulator NOTIFY accumulatorChanged)
Q_PROPERTY(int deadband READ deadband WRITE setDeadband NOTIFY deadbandChanged)
// Property accessors // Property accessors
...@@ -98,6 +99,9 @@ public: ...@@ -98,6 +99,9 @@ public:
bool accumulator(void); bool accumulator(void);
void setAccumulator(bool accu); void setAccumulator(bool accu);
bool deadband(void);
void setDeadband(bool accu);
typedef enum { typedef enum {
CalibrationModeOff, // Not calibrating CalibrationModeOff, // Not calibrating
CalibrationModeMonitor, // Monitors are active, continue to send to vehicle if already polling CalibrationModeMonitor, // Monitors are active, continue to send to vehicle if already polling
...@@ -125,6 +129,8 @@ signals: ...@@ -125,6 +129,8 @@ signals:
void accumulatorChanged(bool accumulator); void accumulatorChanged(bool accumulator);
void deadbandChanged(bool deadband);
void enabledChanged(bool enabled); void enabledChanged(bool enabled);
/// Signal containing new joystick information /// Signal containing new joystick information
...@@ -183,6 +189,7 @@ protected: ...@@ -183,6 +189,7 @@ protected:
bool _exponential; bool _exponential;
bool _accumulator; bool _accumulator;
bool _deadband;
Vehicle* _activeVehicle; Vehicle* _activeVehicle;
bool _pollingStartedForCalibration; bool _pollingStartedForCalibration;
...@@ -198,6 +205,7 @@ private: ...@@ -198,6 +205,7 @@ private:
static const char* _throttleModeSettingsKey; static const char* _throttleModeSettingsKey;
static const char* _exponentialSettingsKey; static const char* _exponentialSettingsKey;
static const char* _accumulatorSettingsKey; static const char* _accumulatorSettingsKey;
static const char* _deadbandSettingsKey;
}; };
#endif #endif
...@@ -72,7 +72,7 @@ SetupPage { ...@@ -72,7 +72,7 @@ SetupPage {
Item { Item {
property int axisValue: 0 property int axisValue: 0
property int deadbandValue: 0
property int __lastAxisValue: 0 property int __lastAxisValue: 0
readonly property int __axisValueMaxJitter: 100 readonly property int __axisValueMaxJitter: 100
...@@ -87,6 +87,20 @@ SetupPage { ...@@ -87,6 +87,20 @@ SetupPage {
color: __barColor color: __barColor
} }
// Deadband
Rectangle {
id: deadbandBar
anchors.verticalCenter: parent.verticalCenter
x: _deadbandPosition
width: _deadbandWidth
height: parent.height / 2
color: "#8c161a"
property real _percentDeadband: ((2 * deadbandValue) / (32768.0 * 2))
property real _deadbandWidth: parent.width * _percentDeadband
property real _deadbandPosition: (parent.width - _deadbandWidth) / 2
}
// Center point // Center point
Rectangle { Rectangle {
anchors.horizontalCenter: parent.horizontalCenter anchors.horizontalCenter: parent.horizontalCenter
...@@ -126,13 +140,15 @@ SetupPage { ...@@ -126,13 +140,15 @@ SetupPage {
duration: 1500 duration: 1500
} }
/*
// Axis value debugger // Axis value debugger
/*
QGCLabel { QGCLabel {
anchors.fill: parent anchors.fill: parent
text: axisValue text: axisValue
} }
*/ */
} }
} // Component - axisMonitorDisplayComponent } // Component - axisMonitorDisplayComponent
...@@ -180,6 +196,8 @@ SetupPage { ...@@ -180,6 +196,8 @@ SetupPage {
target: controller target: controller
onRollAxisValueChanged: rollLoader.item.axisValue = value onRollAxisValueChanged: rollLoader.item.axisValue = value
onRollAxisDeadbandChanged: rollLoader.item.deadbandValue = value
} }
} }
...@@ -210,6 +228,9 @@ SetupPage { ...@@ -210,6 +228,9 @@ SetupPage {
target: controller target: controller
onPitchAxisValueChanged: pitchLoader.item.axisValue = value onPitchAxisValueChanged: pitchLoader.item.axisValue = value
onPitchAxisDeadbandChanged: pitchLoader.item.deadbandValue = value
} }
} }
...@@ -240,6 +261,8 @@ SetupPage { ...@@ -240,6 +261,8 @@ SetupPage {
target: controller target: controller
onYawAxisValueChanged: yawLoader.item.axisValue = value onYawAxisValueChanged: yawLoader.item.axisValue = value
onYawAxisDeadbandChanged: yawLoader.item.deadbandValue = value
} }
} }
...@@ -270,6 +293,8 @@ SetupPage { ...@@ -270,6 +293,8 @@ SetupPage {
target: controller target: controller
onThrottleAxisValueChanged: throttleLoader.item.axisValue = value onThrottleAxisValueChanged: throttleLoader.item.axisValue = value
onThrottleAxisDeadbandChanged: throttleLoader.item.deadbandValue = value
} }
} }
} // Column - Attitude Control labels } // Column - Attitude Control labels
...@@ -383,6 +408,7 @@ SetupPage { ...@@ -383,6 +408,7 @@ SetupPage {
} }
Row { Row {
x: 20
width: parent.width width: parent.width
spacing: ScreenTools.defaultFontPixelWidth spacing: ScreenTools.defaultFontPixelWidth
visible: _activeJoystick.throttleMode == 0 visible: _activeJoystick.throttleMode == 0
...@@ -390,12 +416,27 @@ SetupPage { ...@@ -390,12 +416,27 @@ SetupPage {
QGCCheckBox { QGCCheckBox {
id: accumulator id: accumulator
checked: _activeJoystick.accumulator checked: _activeJoystick.accumulator
text: qsTr("Use accumulator on throttle") text: qsTr("Spring on throttle support")
onClicked: _activeJoystick.accumulator = checked onClicked: _activeJoystick.accumulator = checked
} }
} }
Row {
x: 20
width: parent.width
spacing: ScreenTools.defaultFontPixelWidth
visible: _activeJoystick.throttleMode == 0
QGCCheckBox {
id: deadband
checked: _activeJoystick.deadband
text: qsTr("Deadband (requires re-calibration)")
onClicked: _activeJoystick.deadband = checked
}
}
QGCRadioButton { QGCRadioButton {
exclusiveGroup: throttleModeExclusiveGroup exclusiveGroup: throttleModeExclusiveGroup
text: qsTr("Full down stick is zero throttle") text: qsTr("Full down stick is zero throttle")
...@@ -711,3 +752,5 @@ SetupPage { ...@@ -711,3 +752,5 @@ SetupPage {
} // Item } // Item
} // Component - pageComponent } // Component - pageComponent
} // SetupPage } // SetupPage
...@@ -224,17 +224,49 @@ void JoystickConfigController::_saveAllTrims(void) ...@@ -224,17 +224,49 @@ void JoystickConfigController::_saveAllTrims(void)
_advanceState(); _advanceState();
} }
void JoystickConfigController::_axisDeadbandChanged(int axis, int value)
{
value = abs(value)<_calValidMaxValue?abs(value):_calValidMaxValue;
if (value>_rgAxisInfo[axis].deadband) {
_rgAxisInfo[axis].deadband = value;
switch (_rgAxisInfo[axis].function) {
case Joystick::rollFunction:
emit rollAxisDeadbandChanged(_rgAxisInfo[axis].deadband);
break;
case Joystick::pitchFunction:
emit pitchAxisDeadbandChanged(_rgAxisInfo[axis].deadband);
break;
case Joystick::yawFunction:
emit yawAxisDeadbandChanged(_rgAxisInfo[axis].deadband);
break;
case Joystick::throttleFunction:
emit throttleAxisDeadbandChanged(_rgAxisInfo[axis].deadband);
break;
default:
break;
}
qCDebug(JoystickConfigControllerLog) << "Axis:" << axis << "Deadband:" << _rgAxisInfo[axis].deadband;
}
}
/// @brief Waits for the sticks to be centered, enabling Next when done. /// @brief Waits for the sticks to be centered, enabling Next when done.
void JoystickConfigController::_inputCenterWaitBegin(Joystick::AxisFunction_t function, int axis, int value) void JoystickConfigController::_inputCenterWaitBegin(Joystick::AxisFunction_t function, int axis, int value)
{ {
Q_UNUSED(function); Q_UNUSED(function);
_rgAxisInfo[axis].deadband = std::max(abs(value),_rgAxisInfo[axis].deadband);
//sensing deadband
if (_activeJoystick->deadband()) {
if (abs(value)*1.5>_rgAxisInfo[axis].deadband) {
_axisDeadbandChanged(axis,abs(value)*1.5);
}
}
_nextButton->setEnabled(true); _nextButton->setEnabled(true);
// FIXME: Doesn't wait for center // FIXME: Doesn't wait for center
// FIXME: Ideally the deadband should be probed only around the center // FIXME: Ideally the deadband should be probed only around the center
qCDebug(JoystickConfigControllerLog) << "Axis:" << axis << "Deadband:" << _rgAxisInfo[axis].deadband;
} }
bool JoystickConfigController::_stickSettleComplete(int axis, int value) bool JoystickConfigController::_stickSettleComplete(int axis, int value)
...@@ -669,6 +701,42 @@ int JoystickConfigController::throttleAxisValue(void) ...@@ -669,6 +701,42 @@ int JoystickConfigController::throttleAxisValue(void)
} }
} }
int JoystickConfigController::rollAxisDeadband(void)
{
if (_rgFunctionAxisMapping[Joystick::rollFunction] != _axisNoAxis) {
return _rgAxisInfo[_rgFunctionAxisMapping[Joystick::rollFunction]].deadband;
} else {
return 0;
}
}
int JoystickConfigController::pitchAxisDeadband(void)
{
if (_rgFunctionAxisMapping[Joystick::pitchFunction] != _axisNoAxis) {
return _rgAxisInfo[_rgFunctionAxisMapping[Joystick::pitchFunction]].deadband;
} else {
return 0;
}
}
int JoystickConfigController::yawAxisDeadband(void)
{
if (_rgFunctionAxisMapping[Joystick::yawFunction] != _axisNoAxis) {
return _rgAxisInfo[_rgFunctionAxisMapping[Joystick::yawFunction]].deadband;
} else {
return 0;
}
}
int JoystickConfigController::throttleAxisDeadband(void)
{
if (_rgFunctionAxisMapping[Joystick::throttleFunction] != _axisNoAxis) {
return _rgAxisInfo[_rgFunctionAxisMapping[Joystick::throttleFunction]].deadband;
} else {
return 0;
}
}
bool JoystickConfigController::rollAxisMapped(void) bool JoystickConfigController::rollAxisMapped(void)
{ {
return _rgFunctionAxisMapping[Joystick::rollFunction] != _axisNoAxis; return _rgFunctionAxisMapping[Joystick::rollFunction] != _axisNoAxis;
...@@ -736,6 +804,11 @@ void JoystickConfigController::_signalAllAttiudeValueChanges(void) ...@@ -736,6 +804,11 @@ void JoystickConfigController::_signalAllAttiudeValueChanges(void)
emit pitchAxisReversedChanged(pitchAxisReversed()); emit pitchAxisReversedChanged(pitchAxisReversed());
emit yawAxisReversedChanged(yawAxisReversed()); emit yawAxisReversedChanged(yawAxisReversed());
emit throttleAxisReversedChanged(throttleAxisReversed()); emit throttleAxisReversedChanged(throttleAxisReversed());
emit rollAxisDeadbandChanged(rollAxisDeadband());
emit pitchAxisDeadbandChanged(pitchAxisDeadband());
emit yawAxisDeadbandChanged(yawAxisDeadband());
emit throttleAxisDeadbandChanged(throttleAxisDeadband());
} }
void JoystickConfigController::_activeJoystickChanged(Joystick* joystick) void JoystickConfigController::_activeJoystickChanged(Joystick* joystick)
......
...@@ -57,6 +57,11 @@ public: ...@@ -57,6 +57,11 @@ public:
Q_PROPERTY(int yawAxisValue READ yawAxisValue NOTIFY yawAxisValueChanged) Q_PROPERTY(int yawAxisValue READ yawAxisValue NOTIFY yawAxisValueChanged)
Q_PROPERTY(int throttleAxisValue READ throttleAxisValue NOTIFY throttleAxisValueChanged) Q_PROPERTY(int throttleAxisValue READ throttleAxisValue NOTIFY throttleAxisValueChanged)
Q_PROPERTY(int rollAxisDeadband READ rollAxisDeadband NOTIFY rollAxisDeadbandChanged)
Q_PROPERTY(int pitchAxisDeadband READ pitchAxisDeadband NOTIFY pitchAxisDeadbandChanged)
Q_PROPERTY(int yawAxisDeadband READ yawAxisDeadband NOTIFY yawAxisDeadbandChanged)
Q_PROPERTY(int throttleAxisDeadband READ throttleAxisDeadband NOTIFY throttleAxisDeadbandChanged)
Q_PROPERTY(int rollAxisReversed READ rollAxisReversed NOTIFY rollAxisReversedChanged) Q_PROPERTY(int rollAxisReversed READ rollAxisReversed NOTIFY rollAxisReversedChanged)
Q_PROPERTY(int pitchAxisReversed READ pitchAxisReversed NOTIFY pitchAxisReversedChanged) Q_PROPERTY(int pitchAxisReversed READ pitchAxisReversed NOTIFY pitchAxisReversedChanged)
Q_PROPERTY(int yawAxisReversed READ yawAxisReversed NOTIFY yawAxisReversedChanged) Q_PROPERTY(int yawAxisReversed READ yawAxisReversed NOTIFY yawAxisReversedChanged)
...@@ -74,6 +79,11 @@ public: ...@@ -74,6 +79,11 @@ public:
int yawAxisValue(void); int yawAxisValue(void);
int throttleAxisValue(void); int throttleAxisValue(void);
int rollAxisDeadband(void);
int pitchAxisDeadband(void);
int yawAxisDeadband(void);
int throttleAxisDeadband(void);
bool rollAxisMapped(void); bool rollAxisMapped(void);
bool pitchAxisMapped(void); bool pitchAxisMapped(void);
bool yawAxisMapped(void); bool yawAxisMapped(void);
...@@ -99,6 +109,11 @@ signals: ...@@ -99,6 +109,11 @@ signals:
void yawAxisValueChanged(int value); void yawAxisValueChanged(int value);
void throttleAxisValueChanged(int value); void throttleAxisValueChanged(int value);
void rollAxisDeadbandChanged(int value);
void pitchAxisDeadbandChanged(int value);
void yawAxisDeadbandChanged(int value);
void throttleAxisDeadbandChanged(int value);
void rollAxisReversedChanged(bool reversed); void rollAxisReversedChanged(bool reversed);
void pitchAxisReversedChanged(bool reversed); void pitchAxisReversedChanged(bool reversed);
void yawAxisReversedChanged(bool reversed); void yawAxisReversedChanged(bool reversed);
...@@ -112,6 +127,7 @@ signals: ...@@ -112,6 +127,7 @@ signals:
private slots: private slots:
void _activeJoystickChanged(Joystick* joystick); void _activeJoystickChanged(Joystick* joystick);
void _axisValueChanged(int axis, int value); void _axisValueChanged(int axis, int value);
void _axisDeadbandChanged(int axis, int value);
private: private:
/// @brief The states of the calibration state machine. /// @brief The states of the calibration state machine.
......
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