Commit eb30a3a7 authored by Gus Grubba's avatar Gus Grubba

Keep track of gimbal position locally.

parent 33fbd552
...@@ -680,6 +680,7 @@ void Joystick::startPolling(Vehicle* vehicle) ...@@ -680,6 +680,7 @@ void Joystick::startPolling(Vehicle* vehicle)
disconnect(this, &Joystick::gimbalPitchStep, _activeVehicle, &Vehicle::gimbalPitchStep); disconnect(this, &Joystick::gimbalPitchStep, _activeVehicle, &Vehicle::gimbalPitchStep);
disconnect(this, &Joystick::gimbalYawStep, _activeVehicle, &Vehicle::gimbalYawStep); disconnect(this, &Joystick::gimbalYawStep, _activeVehicle, &Vehicle::gimbalYawStep);
disconnect(this, &Joystick::centerGimbal, _activeVehicle, &Vehicle::centerGimbal); disconnect(this, &Joystick::centerGimbal, _activeVehicle, &Vehicle::centerGimbal);
disconnect(this, &Joystick::gimbalControlValue, _activeVehicle, &Vehicle::gimbalControlValue);
} }
// Always set up the new vehicle // Always set up the new vehicle
_activeVehicle = vehicle; _activeVehicle = vehicle;
...@@ -700,6 +701,7 @@ void Joystick::startPolling(Vehicle* vehicle) ...@@ -700,6 +701,7 @@ void Joystick::startPolling(Vehicle* vehicle)
connect(this, &Joystick::gimbalPitchStep, _activeVehicle, &Vehicle::gimbalPitchStep); connect(this, &Joystick::gimbalPitchStep, _activeVehicle, &Vehicle::gimbalPitchStep);
connect(this, &Joystick::gimbalYawStep, _activeVehicle, &Vehicle::gimbalYawStep); connect(this, &Joystick::gimbalYawStep, _activeVehicle, &Vehicle::gimbalYawStep);
connect(this, &Joystick::centerGimbal, _activeVehicle, &Vehicle::centerGimbal); connect(this, &Joystick::centerGimbal, _activeVehicle, &Vehicle::centerGimbal);
connect(this, &Joystick::gimbalControlValue, _activeVehicle, &Vehicle::gimbalControlValue);
// FIXME: **** // FIXME: ****
//connect(this, &Joystick::buttonActionTriggered, uas, &UAS::triggerAction); //connect(this, &Joystick::buttonActionTriggered, uas, &UAS::triggerAction);
} }
...@@ -724,6 +726,7 @@ void Joystick::stopPolling(void) ...@@ -724,6 +726,7 @@ void Joystick::stopPolling(void)
disconnect(this, &Joystick::gimbalPitchStep, _activeVehicle, &Vehicle::gimbalPitchStep); disconnect(this, &Joystick::gimbalPitchStep, _activeVehicle, &Vehicle::gimbalPitchStep);
disconnect(this, &Joystick::gimbalYawStep, _activeVehicle, &Vehicle::gimbalYawStep); disconnect(this, &Joystick::gimbalYawStep, _activeVehicle, &Vehicle::gimbalYawStep);
disconnect(this, &Joystick::centerGimbal, _activeVehicle, &Vehicle::centerGimbal); disconnect(this, &Joystick::centerGimbal, _activeVehicle, &Vehicle::centerGimbal);
disconnect(this, &Joystick::gimbalControlValue, _activeVehicle, &Vehicle::gimbalControlValue);
} }
// FIXME: **** // FIXME: ****
//disconnect(this, &Joystick::buttonActionTriggered, uas, &UAS::triggerAction); //disconnect(this, &Joystick::buttonActionTriggered, uas, &UAS::triggerAction);
...@@ -1003,20 +1006,39 @@ void Joystick::_executeButtonAction(const QString& action) ...@@ -1003,20 +1006,39 @@ void Joystick::_executeButtonAction(const QString& action)
} else if(action == _buttonActionToggleVideoRecord) { } else if(action == _buttonActionToggleVideoRecord) {
emit toggleVideoRecord(); emit toggleVideoRecord();
} else if(action == _buttonActionGimbalUp) { } else if(action == _buttonActionGimbalUp) {
emit gimbalPitchStep(1); _pitchStep(1);
} else if(action == _buttonActionGimbalDown) { } else if(action == _buttonActionGimbalDown) {
emit gimbalPitchStep(-1); _pitchStep(-1);
} else if(action == _buttonActionGimbalLeft) { } else if(action == _buttonActionGimbalLeft) {
emit gimbalYawStep(-1); _yawStep(-1);
} else if(action == _buttonActionGimbalRight) { } else if(action == _buttonActionGimbalRight) {
emit gimbalYawStep(1); _yawStep(1);
} else if(action == _buttonActionGimbalCenter) { } else if(action == _buttonActionGimbalCenter) {
emit centerGimbal(); _localPitch = 0.0;
_localYaw = 0.0;
emit gimbalControlValue(0.0, 0.0);
} else { } else {
qCDebug(JoystickLog) << "_buttonAction unknown action:" << action; qCDebug(JoystickLog) << "_buttonAction unknown action:" << action;
} }
} }
void Joystick::_pitchStep(int direction)
{
_localPitch += static_cast<double>(direction);
//-- Arbitrary range
if(_localPitch < -90.0) _localPitch = -90.0;
if(_localPitch > 35.0) _localPitch = 35.0;
emit gimbalControlValue(_localPitch, _localYaw);
}
void Joystick::_yawStep(int direction)
{
_localYaw += static_cast<double>(direction);
if(_localYaw < -180.0) _localYaw = -180.0;
if(_localYaw > 180.0) _localYaw = 180.0;
emit gimbalControlValue(_localPitch, _localYaw);
}
bool Joystick::_validAxis(int axis) bool Joystick::_validAxis(int axis)
{ {
if(axis >= 0 && axis < _axisCount) { if(axis >= 0 && axis < _axisCount) {
......
...@@ -213,6 +213,7 @@ signals: ...@@ -213,6 +213,7 @@ signals:
void gimbalPitchStep (int direction); void gimbalPitchStep (int direction);
void gimbalYawStep (int direction); void gimbalYawStep (int direction);
void centerGimbal (); void centerGimbal ();
void gimbalControlValue (double pitch, double yaw);
void setArmed (bool arm); void setArmed (bool arm);
void setVtolInFwdFlight (bool set); void setVtolInFwdFlight (bool set);
void setFlightMode (const QString& flightMode); void setFlightMode (const QString& flightMode);
...@@ -230,6 +231,11 @@ protected: ...@@ -230,6 +231,11 @@ protected:
void _handleAxis (); void _handleAxis ();
void _handleButtons (); void _handleButtons ();
void _pitchStep (int direction);
void _yawStep (int direction);
double _localYaw = 0.0;
double _localPitch = 0.0;
private: private:
virtual bool _open () = 0; virtual bool _open () = 0;
virtual void _close () = 0; virtual void _close () = 0;
...@@ -290,6 +296,7 @@ protected: ...@@ -290,6 +296,7 @@ protected:
QStringList _availableActionTitles; QStringList _availableActionTitles;
MultiVehicleManager* _multiVehicleManager = nullptr; MultiVehicleManager* _multiVehicleManager = nullptr;
private: private:
static const char* _rgFunctionSettingsKey[maxFunction]; static const char* _rgFunctionSettingsKey[maxFunction];
......
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