Unverified Commit 78922bd8 authored by Gus Grubba's avatar Gus Grubba Committed by GitHub

Merge pull request #7595 from mavlink/joystickMakeOver

Joystick make over
parents 041887d0 c4b58dd5
......@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build
* Rework joysticks. Fixed several issues and updated setup UI.
* Adding support for UDP RTP h.265 video streams
* For text to speech engine on Linux to English (all messages are in English)
* Automated the ingestion of localization from Crowdin
......
......@@ -98,48 +98,4 @@
<qresource prefix="/opengl">
<file>resources/opengl/buglist.json</file>
</qresource>
<qresource prefix="/qml/calibration/joystick/mode1">
<file alias="joystickCenter.png">resources/calibration/joystick/mode1/joystickCenter.png</file>
<file alias="joystickPitchDown.png">resources/calibration/joystick/mode1/joystickPitchDown.png</file>
<file alias="joystickPitchUp.png">resources/calibration/joystick/mode1/joystickPitchUp.png</file>
<file alias="joystickRollLeft.png">resources/calibration/joystick/mode1/joystickRollLeft.png</file>
<file alias="joystickRollRight.png">resources/calibration/joystick/mode1/joystickRollRight.png</file>
<file alias="joystickThrottleDown.png">resources/calibration/joystick/mode1/joystickThrottleDown.png</file>
<file alias="joystickThrottleUp.png">resources/calibration/joystick/mode1/joystickThrottleUp.png</file>
<file alias="joystickYawLeft.png">resources/calibration/joystick/mode1/joystickYawLeft.png</file>
<file alias="joystickYawRight.png">resources/calibration/joystick/mode1/joystickYawRight.png</file>
</qresource>
<qresource prefix="/qml/calibration/joystick/mode2">
<file alias="joystickCenter.png">resources/calibration/joystick/mode2/joystickCenter.png</file>
<file alias="joystickPitchDown.png">resources/calibration/joystick/mode2/joystickPitchDown.png</file>
<file alias="joystickPitchUp.png">resources/calibration/joystick/mode2/joystickPitchUp.png</file>
<file alias="joystickRollLeft.png">resources/calibration/joystick/mode2/joystickRollLeft.png</file>
<file alias="joystickRollRight.png">resources/calibration/joystick/mode2/joystickRollRight.png</file>
<file alias="joystickThrottleDown.png">resources/calibration/joystick/mode2/joystickThrottleDown.png</file>
<file alias="joystickThrottleUp.png">resources/calibration/joystick/mode2/joystickThrottleUp.png</file>
<file alias="joystickYawLeft.png">resources/calibration/joystick/mode2/joystickYawLeft.png</file>
<file alias="joystickYawRight.png">resources/calibration/joystick/mode2/joystickYawRight.png</file>
</qresource>
<qresource prefix="/qml/calibration/joystick/mode3">
<file alias="joystickCenter.png">resources/calibration/joystick/mode3/joystickCenter.png</file>
<file alias="joystickPitchDown.png">resources/calibration/joystick/mode3/joystickPitchDown.png</file>
<file alias="joystickPitchUp.png">resources/calibration/joystick/mode3/joystickPitchUp.png</file>
<file alias="joystickRollLeft.png">resources/calibration/joystick/mode3/joystickRollLeft.png</file>
<file alias="joystickRollRight.png">resources/calibration/joystick/mode3/joystickRollRight.png</file>
<file alias="joystickThrottleDown.png">resources/calibration/joystick/mode3/joystickThrottleDown.png</file>
<file alias="joystickThrottleUp.png">resources/calibration/joystick/mode3/joystickThrottleUp.png</file>
<file alias="joystickYawLeft.png">resources/calibration/joystick/mode3/joystickYawLeft.png</file>
<file alias="joystickYawRight.png">resources/calibration/joystick/mode3/joystickYawRight.png</file>
</qresource>
<qresource prefix="/qml/calibration/joystick/mode4">
<file alias="joystickCenter.png">resources/calibration/joystick/mode4/joystickCenter.png</file>
<file alias="joystickPitchDown.png">resources/calibration/joystick/mode4/joystickPitchDown.png</file>
<file alias="joystickPitchUp.png">resources/calibration/joystick/mode4/joystickPitchUp.png</file>
<file alias="joystickRollLeft.png">resources/calibration/joystick/mode4/joystickRollLeft.png</file>
<file alias="joystickRollRight.png">resources/calibration/joystick/mode4/joystickRollRight.png</file>
<file alias="joystickThrottleDown.png">resources/calibration/joystick/mode4/joystickThrottleDown.png</file>
<file alias="joystickThrottleUp.png">resources/calibration/joystick/mode4/joystickThrottleUp.png</file>
<file alias="joystickYawLeft.png">resources/calibration/joystick/mode4/joystickYawLeft.png</file>
<file alias="joystickYawRight.png">resources/calibration/joystick/mode4/joystickYawRight.png</file>
</qresource>
</RCC>
......@@ -38,6 +38,10 @@
<file alias="HealthPageWidget.qml">src/FlightMap/Widgets/HealthPageWidget.qml</file>
<file alias="HelpSettings.qml">src/ui/preferences/HelpSettings.qml</file>
<file alias="JoystickConfig.qml">src/VehicleSetup/JoystickConfig.qml</file>
<file alias="JoystickConfigButtons.qml">src/VehicleSetup/JoystickConfigButtons.qml</file>
<file alias="JoystickConfigAdvanced.qml">src/VehicleSetup/JoystickConfigAdvanced.qml</file>
<file alias="JoystickConfigGeneral.qml">src/VehicleSetup/JoystickConfigGeneral.qml</file>
<file alias="JoystickConfigCalibration.qml">src/VehicleSetup/JoystickConfigCalibration.qml</file>
<file alias="LinkSettings.qml">src/ui/preferences/LinkSettings.qml</file>
<file alias="LogDownloadPage.qml">src/AnalyzeView/LogDownloadPage.qml</file>
<file alias="LogReplaySettings.qml">src/ui/preferences/LogReplaySettings.qml</file>
......@@ -60,6 +64,7 @@
<file alias="QGCViewDialogContainer.qml">src/QmlControls/QGCViewDialogContainer.qml</file>
<file alias="QGroundControl/Controls/AnalyzePage.qml">src/AnalyzeView/AnalyzePage.qml</file>
<file alias="QGroundControl/Controls/AppMessages.qml">src/QmlControls/AppMessages.qml</file>
<file alias="QGroundControl/Controls/AxisMonitor.qml">src/QmlControls/AxisMonitor.qml</file>
<file alias="QGroundControl/Controls/CameraCalc.qml">src/PlanView/CameraCalc.qml</file>
<file alias="QGroundControl/Controls/CameraSection.qml">src/PlanView/CameraSection.qml</file>
<file alias="QGroundControl/Controls/ClickableColor.qml">src/QmlControls/ClickableColor.qml</file>
......@@ -120,6 +125,8 @@
<file alias="QGroundControl/Controls/QGCRadioButton.qml">src/QmlControls/QGCRadioButton.qml</file>
<file alias="QGroundControl/Controls/QGCSlider.qml">src/QmlControls/QGCSlider.qml</file>
<file alias="QGroundControl/Controls/QGCSwitch.qml">src/QmlControls/QGCSwitch.qml</file>
<file alias="QGroundControl/Controls/QGCTabBar.qml">src/QmlControls/QGCTabBar.qml</file>
<file alias="QGroundControl/Controls/QGCTabButton.qml">src/QmlControls/QGCTabButton.qml</file>
<file alias="QGroundControl/Controls/QGCTextField.qml">src/QmlControls/QGCTextField.qml</file>
<file alias="QGroundControl/Controls/QGCToolBarButton.qml">src/QmlControls/QGCToolBarButton.qml</file>
<file alias="QGroundControl/Controls/QGCViewDialog.qml">src/QmlControls/QGCViewDialog.qml</file>
......
......@@ -378,15 +378,63 @@ QGCCameraManager::_activeJoystickChanged(Joystick* joystick)
{
qCDebug(CameraManagerLog) << "Joystick changed";
if(_activeJoystick) {
disconnect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom);
disconnect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera);
disconnect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream);
disconnect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom);
disconnect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera);
disconnect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream);
disconnect(_activeJoystick, &Joystick::triggerCamera, this, &QGCCameraManager::_triggerCamera);
disconnect(_activeJoystick, &Joystick::startVideoRecord, this, &QGCCameraManager::_startVideoRecording);
disconnect(_activeJoystick, &Joystick::stopVideoRecord, this, &QGCCameraManager::_stopVideoRecording);
disconnect(_activeJoystick, &Joystick::toggleVideoRecord, this, &QGCCameraManager::_toggleVideoRecording);
}
_activeJoystick = joystick;
if(_activeJoystick) {
connect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom);
connect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera);
connect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream);
connect(_activeJoystick, &Joystick::stepZoom, this, &QGCCameraManager::_stepZoom);
connect(_activeJoystick, &Joystick::stepCamera, this, &QGCCameraManager::_stepCamera);
connect(_activeJoystick, &Joystick::stepStream, this, &QGCCameraManager::_stepStream);
connect(_activeJoystick, &Joystick::triggerCamera, this, &QGCCameraManager::_triggerCamera);
connect(_activeJoystick, &Joystick::startVideoRecord, this, &QGCCameraManager::_startVideoRecording);
connect(_activeJoystick, &Joystick::stopVideoRecord, this, &QGCCameraManager::_stopVideoRecording);
connect(_activeJoystick, &Joystick::toggleVideoRecord, this, &QGCCameraManager::_toggleVideoRecording);
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_triggerCamera()
{
QGCCameraControl* pCamera = currentCameraInstance();
if(pCamera) {
pCamera->takePhoto();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_startVideoRecording()
{
QGCCameraControl* pCamera = currentCameraInstance();
if(pCamera) {
pCamera->startVideo();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_stopVideoRecording()
{
QGCCameraControl* pCamera = currentCameraInstance();
if(pCamera) {
pCamera->stopVideo();
}
}
//-----------------------------------------------------------------------------
void
QGCCameraManager::_toggleVideoRecording()
{
QGCCameraControl* pCamera = currentCameraInstance();
if(pCamera) {
pCamera->toggleVideo();
}
}
......
......@@ -60,6 +60,10 @@ protected slots:
virtual void _stepCamera (int direction);
virtual void _stepStream (int direction);
virtual void _cameraTimeout ();
virtual void _triggerCamera ();
virtual void _startVideoRecording ();
virtual void _stopVideoRecording ();
virtual void _toggleVideoRecording ();
protected:
virtual QGCCameraControl* _findCamera (int id);
......
This diff is collapsed.
This diff is collapsed.
......@@ -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
......
import QtQuick 2.11
import QtQuick.Controls 2.4
import QGroundControl 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
Item {
property int axisValue: 0
property int deadbandValue: 0
property bool narrowIndicator: false
property color deadbandColor: "#8c161a"
property bool mapped: false
property bool reversed: false
property color __barColor: qgcPal.windowShade
// Bar
Rectangle {
id: bar
anchors.verticalCenter: parent.verticalCenter
width: parent.width
height: parent.height / 2
color: __barColor
}
// Deadband
Rectangle {
id: deadbandBar
anchors.verticalCenter: parent.verticalCenter
x: _deadbandPosition
width: _deadbandWidth
height: parent.height / 2
color: deadbandColor
visible: controller.deadbandToggle
property real _percentDeadband: ((2 * deadbandValue) / (32768.0 * 2))
property real _deadbandWidth: parent.width * _percentDeadband
property real _deadbandPosition: (parent.width - _deadbandWidth) / 2
}
// Center point
Rectangle {
anchors.horizontalCenter: parent.horizontalCenter
width: ScreenTools.defaultFontPixelWidth / 2
height: parent.height
color: qgcPal.window
}
// Indicator
Rectangle {
anchors.verticalCenter: parent.verticalCenter
width: parent.narrowIndicator ? height/6 : height
height: parent.height * 0.75
x: (reversed ? (parent.width - _indicatorPosition) : _indicatorPosition) - (width / 2)
radius: width / 2
color: qgcPal.text
visible: mapped
property real _percentAxisValue: ((axisValue + 32768.0) / (32768.0 * 2))
property real _indicatorPosition: parent.width * _percentAxisValue
}
QGCLabel {
anchors.fill: parent
horizontalAlignment: Text.AlignHCenter
verticalAlignment: Text.AlignVCenter
text: qsTr("Not Mapped")
visible: !mapped
}
ColorAnimation {
id: barAnimation
target: bar
property: "color"
from: "yellow"
to: __barColor
duration: 1500
}
// Axis value debugger
/*
QGCLabel {
anchors.fill: parent
text: axisValue
}
*/
}
import QtQuick 2.11
import QtQuick.Controls 2.4
import QGroundControl 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
TabBar {
background: Rectangle {
color: qgcPal.window
}
}
import QtQuick 2.11
import QtQuick.Controls 2.4
import QGroundControl 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
TabButton {
id: control
property bool _showHighlight: (pressed | hovered | checked)
background: Rectangle {
color: _showHighlight ? qgcPal.buttonHighlight : qgcPal.button
}
contentItem: QGCLabel {
text: control.text
color: _showHighlight ? qgcPal.buttonHighlightText : qgcPal.buttonText
horizontalAlignment: Text.AlignHCenter
verticalAlignment: Text.AlignVCenter
elide: Text.ElideRight
}
}
......@@ -2,6 +2,7 @@ Module QGroundControl.Controls
AnalyzePage 1.0 AnalyzePage.qml
AppMessages 1.0 AppMessages.qml
AxisMonitor 1.0 AxisMonitor.qml
CameraCalc 1.0 CameraCalc.qml
APMSubMotorDisplay 1.0 APMSubMotorDisplay.qml
CameraSection 1.0 CameraSection.qml
......@@ -59,6 +60,8 @@ QGCPipable 1.0 QGCPipable.qml
QGCRadioButton 1.0 QGCRadioButton.qml
QGCSlider 1.0 QGCSlider.qml
QGCSwitch 1.0 QGCSwitch.qml
QGCTabBar 1.0 QGCTabBar.qml
QGCTabButton 1.0 QGCTabButton.qml
QGCTextField 1.0 QGCTextField.qml
QGCToolBarButton 1.0 QGCToolBarButton.qml
QGCViewDialog 1.0 QGCViewDialog.qml
......
This diff is collapsed.
......@@ -36,6 +36,7 @@ class UASMessage;
class SettingsManager;
class ADSBVehicle;
class QGCCameraManager;
class Joystick;
#if defined(QGC_AIRMAP_ENABLED)
class AirspaceVehicleManager;
#endif
......@@ -632,6 +633,10 @@ public:
Q_PROPERTY(quint64 mavlinkReceivedCount READ mavlinkReceivedCount NOTIFY mavlinkStatusChanged)
Q_PROPERTY(quint64 mavlinkLossCount READ mavlinkLossCount NOTIFY mavlinkStatusChanged)
Q_PROPERTY(float mavlinkLossPercent READ mavlinkLossPercent NOTIFY mavlinkStatusChanged)
Q_PROPERTY(qreal gimbalRoll READ gimbalRoll NOTIFY gimbalRollChanged)
Q_PROPERTY(qreal gimbalPitch READ gimbalPitch NOTIFY gimbalPitchChanged)
Q_PROPERTY(qreal gimbalYaw READ gimbalYaw NOTIFY gimbalYawChanged)
Q_PROPERTY(bool gimbalData READ gimbalData NOTIFY gimbalDataChanged)
// The following properties relate to Orbit status
Q_PROPERTY(bool orbitActive READ orbitActive NOTIFY orbitActiveChanged)
......@@ -761,7 +766,10 @@ public:
Q_INVOKABLE void setPIDTuningTelemetryMode(bool pidTuning);
Q_INVOKABLE void gimbalControlValue(double pitch, double yaw);
Q_INVOKABLE void gimbalControlValue (double pitch, double yaw);
Q_INVOKABLE void gimbalPitchStep (int direction);
Q_INVOKABLE void gimbalYawStep (int direction);
Q_INVOKABLE void centerGimbal ();
#if !defined(NO_ARDUPILOT_DIALECT)
Q_INVOKABLE void flashBootloader(void);
......@@ -832,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);
......@@ -1076,7 +1084,6 @@ public:
void _setFlying(bool flying);
void _setLanding(bool landing);
void setVtolInFwdFlight(bool vtolInFwdFlight);
void _setHomePosition(QGeoCoordinate& homeCoord);
void _setMaxProtoVersion (unsigned version);
......@@ -1088,6 +1095,14 @@ public:
quint64 mavlinkLossCount () { return _mavlinkLossCount; } /// Total number of lost messages
float mavlinkLossPercent () { return _mavlinkLossPercent; } /// Running loss rate
qreal gimbalRoll () { return static_cast<qreal>(_curGimbalRoll);}
qreal gimbalPitch () { return static_cast<qreal>(_curGimbalPitch); }
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);
......@@ -1192,8 +1207,13 @@ signals:
void mavlinkSerialControl(uint8_t device, uint8_t flags, uint16_t timeout, uint32_t baudrate, QByteArray data);
// MAVLink protocol version
void requestProtocolVersion(unsigned version);
void mavlinkStatusChanged();
void requestProtocolVersion (unsigned version);
void mavlinkStatusChanged ();
void gimbalRollChanged ();
void gimbalPitchChanged ();
void gimbalYawChanged ();
void gimbalDataChanged ();
private slots:
void _mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message);
......@@ -1235,8 +1255,9 @@ private slots:
void _protocolVersionTimeOut(void);
private:
bool _containsLink(LinkInterface* link);
void _addLink(LinkInterface* link);
bool _containsLink (LinkInterface* link);
void _addLink (LinkInterface* link);
void _joystickChanged (Joystick* joystick);
void _loadSettings(void);
void _saveSettings(void);
void _startJoystick(bool start);
......@@ -1273,6 +1294,7 @@ private:
void _handleStatusText(mavlink_message_t& message, bool longVersion);
void _handleOrbitExecutionStatus(const mavlink_message_t& message);
void _handleMessageInterval(const mavlink_message_t& message);
void _handleGimbalOrientation(const mavlink_message_t& message);
// ArduPilot dialect messages
#if !defined(NO_ARDUPILOT_DIALECT)
void _handleCameraFeedback(const mavlink_message_t& message);
......@@ -1456,6 +1478,12 @@ private:
uint8_t _compID;
bool _heardFrom;
float _curGimbalRoll = 0.0f;
float _curGimbalPitch = 0.0f;
float _curGinmbalYaw = 0.0f;
bool _haveGimbalData = false;
Joystick* _activeJoystick = nullptr;
int _firmwareMajorVersion;
int _firmwareMinorVersion;
int _firmwarePatchVersion;
......
This diff is collapsed.
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.11
import QtQuick.Controls 2.4
import QtQuick.Dialogs 1.3
import QtQuick.Layouts 1.11
import QGroundControl 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
Item {
width: grid.width + (ScreenTools.defaultFontPixelWidth * 2)
height: grid.height + (ScreenTools.defaultFontPixelHeight * 2)
//---------------------------------------------------------------------
GridLayout {
id: grid
columns: 2
columnSpacing: ScreenTools.defaultFontPixelWidth
rowSpacing: ScreenTools.defaultFontPixelHeight
anchors.centerIn: parent
//-------------------------------------------------------------
//-------------------------------------------------------------
QGCRadioButton {
text: qsTr("Full down stick is zero throttle")
checked: _activeJoystick ? _activeJoystick.throttleMode === 1 : false
onClicked: _activeJoystick.throttleMode = 1
Layout.columnSpan: 2
}
QGCRadioButton {
text: qsTr("Center stick is zero throttle")
checked: _activeJoystick ? _activeJoystick.throttleMode === 0 : false
onClicked: _activeJoystick.throttleMode = 0
Layout.columnSpan: 2
}
//-------------------------------------------------------------
QGCLabel {
text: qsTr("Spring loaded throttle smoothing")
visible: _activeJoystick ? _activeJoystick.throttleMode === 0 : false
Layout.alignment: Qt.AlignVCenter
Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 36
}
QGCCheckBox {
checked: _activeJoystick ? _activeJoystick.accumulator : false
visible: _activeJoystick ? _activeJoystick.throttleMode === 0 : false
onClicked: _activeJoystick.accumulator = checked
}
//-------------------------------------------------------------
QGCLabel {
text: qsTr("Allow negative Thrust")
visible: activeVehicle.supportsNegativeThrust
Layout.alignment: Qt.AlignVCenter
}
QGCCheckBox {
visible: activeVehicle.supportsNegativeThrust
enabled: _activeJoystick.negativeThrust = activeVehicle.supportsNegativeThrust
checked: _activeJoystick ? _activeJoystick.negativeThrust : false
onClicked: _activeJoystick.negativeThrust = checked
}
//---------------------------------------------------------------------
QGCLabel {
text: qsTr("Exponential:")
}
Row {
spacing: ScreenTools.defaultFontPixelWidth
QGCSlider {
id: expoSlider
width: ScreenTools.defaultFontPixelWidth * 20
minimumValue: 0
maximumValue: 0.75
Component.onCompleted: value = -_activeJoystick.exponential
onValueChanged: _activeJoystick.exponential = -value
}
QGCLabel {
id: expoSliderIndicator
text: expoSlider.value.toFixed(2)
}
}
//-----------------------------------------------------------------
//-- Enable Advanced Mode
QGCLabel {
text: qsTr("Enable further advanced settings (careful!)")
Layout.alignment: Qt.AlignVCenter
Layout.minimumWidth: ScreenTools.defaultFontPixelWidth * 36
}
QGCCheckBox {
id: advancedSettings
checked: activeVehicle.joystickMode !== 0
onClicked: {
if (!checked) {
activeVehicle.joystickMode = 0
}
}
}
//---------------------------------------------------------------------
//-- 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 {
Layout.alignment: Qt.AlignVCenter
text: qsTr("Joystick mode:")
visible: advancedSettings.checked
}
QGCComboBox {
enabled: advancedSettings.checked
currentIndex: activeVehicle.joystickMode
width: ScreenTools.defaultFontPixelWidth * 20
model: activeVehicle.joystickModes
onActivated: activeVehicle.joystickMode = index
Layout.alignment: Qt.AlignVCenter
visible: advancedSettings.checked
}
//-----------------------------------------------------------------
//-- Message Frequency
QGCLabel {
text: qsTr("Message frequency (Hz):")
Layout.alignment: Qt.AlignVCenter
visible: advancedSettings.checked
}
QGCTextField {
text: _activeJoystick.frequency
enabled: advancedSettings.checked
validator: DoubleValidator { bottom: 0.25; top: 100.0; }
inputMethodHints: Qt.ImhFormattedNumbersOnly
Layout.alignment: Qt.AlignVCenter
onEditingFinished: {
_activeJoystick.frequency = parseFloat(text)
}
visible: advancedSettings.checked
}
//-----------------------------------------------------------------
//-- Enable circle correction
QGCLabel {
text: qsTr("Enable circle correction")
Layout.alignment: Qt.AlignVCenter
visible: advancedSettings.checked
}
QGCCheckBox {
checked: activeVehicle.joystickMode !== 0
enabled: advancedSettings.checked
Component.onCompleted: {
checked = _activeJoystick.circleCorrection
}
onClicked: {
_activeJoystick.circleCorrection = checked
}
visible: advancedSettings.checked
}
//-----------------------------------------------------------------
//-- Deadband
QGCLabel {
text: qsTr("Deadbands")
Layout.alignment: Qt.AlignVCenter
visible: advancedSettings.checked
}
QGCCheckBox {
enabled: advancedSettings.checked
checked: controller.deadbandToggle
onClicked: controller.deadbandToggle = checked
Layout.alignment: Qt.AlignVCenter
visible: advancedSettings.checked
}
QGCLabel{
Layout.fillWidth: true
Layout.columnSpan: 2
font.pointSize: ScreenTools.smallFontPointSize
wrapMode: Text.WordWrap
visible: advancedSettings.checked
text: qsTr("Deadband can be set during the first ") +
qsTr("step of calibration by gently wiggling each axis. ") +
qsTr("Deadband can also be adjusted by clicking and ") +
qsTr("dragging vertically on the corresponding axis monitor.")
}
}
}
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
import QtQuick 2.11
import QtQuick.Controls 2.4
import QtQuick.Dialogs 1.3
import QtQuick.Layouts 1.11
import QGroundControl 1.0
import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
Item {
width: availableWidth
height: (activeVehicle.supportsJSButton ? buttonCol.height : buttonFlow.height) + (ScreenTools.defaultFontPixelHeight * 2)
Connections {
target: _activeJoystick
onRawButtonPressedChanged: {
if (buttonActionRepeater.itemAt(index)) {
buttonActionRepeater.itemAt(index).pressed = pressed
}
if (jsButtonActionRepeater.itemAt(index)) {
jsButtonActionRepeater.itemAt(index).pressed = pressed
}
}
}
Flow {
id: buttonFlow
width: parent.width
spacing: ScreenTools.defaultFontPixelWidth
visible: !activeVehicle.supportsJSButton
anchors.centerIn: parent
Repeater {
id: buttonActionRepeater
model: _activeJoystick ? Math.min(_activeJoystick.totalButtonCount, _maxButtons) : []
Row {
spacing: ScreenTools.defaultFontPixelWidth
property bool pressed
QGCCheckBox {
anchors.verticalCenter: parent.verticalCenter
checked: _activeJoystick ? _activeJoystick.buttonActions[modelData] !== "" : false
onClicked: _activeJoystick.setButtonAction(modelData, checked ? buttonActionCombo.textAt(buttonActionCombo.currentIndex) : "")
}
Rectangle {
anchors.verticalCenter: parent.verticalCenter
width: ScreenTools.defaultFontPixelHeight * 1.5
height: width
border.width: 1
border.color: qgcPal.text
color: pressed ? qgcPal.buttonHighlight : qgcPal.button
QGCLabel {
anchors.fill: parent
color: pressed ? qgcPal.buttonHighlightText : qgcPal.buttonText
horizontalAlignment: Text.AlignHCenter
verticalAlignment: Text.AlignVCenter
text: modelData
}
}
QGCComboBox {
id: buttonActionCombo
width: ScreenTools.defaultFontPixelWidth * 26
model: _activeJoystick ? _activeJoystick.actions : 0
onActivated: _activeJoystick.setButtonAction(modelData, textAt(index))
Component.onCompleted: currentIndex = find(_activeJoystick.buttonActions[modelData])
}
}
}
}
Column {
id: buttonCol
width: parent.width
visible: activeVehicle.supportsJSButton
spacing: ScreenTools.defaultFontPixelHeight / 3
Row {
spacing: ScreenTools.defaultFontPixelWidth
QGCLabel {
horizontalAlignment: Text.AlignHCenter
width: ScreenTools.defaultFontPixelHeight * 1.5
text: qsTr("#")
}
QGCLabel {
width: ScreenTools.defaultFontPixelWidth * 15
text: qsTr("Function: ")
}
QGCLabel {
width: ScreenTools.defaultFontPixelWidth * 15
text: qsTr("Shift Function: ")
}
}
Repeater {
id: jsButtonActionRepeater
model: _activeJoystick ? Math.min(_activeJoystick.totalButtonCount, _maxButtons) : 0
Row {
spacing: ScreenTools.defaultFontPixelWidth
visible: activeVehicle.supportsJSButton
property bool pressed
Rectangle {
anchors.verticalCenter: parent.verticalCenter
width: ScreenTools.defaultFontPixelHeight * 1.5
height: width
border.width: 1
border.color: qgcPal.text
color: pressed ? qgcPal.buttonHighlight : qgcPal.button
QGCLabel {
anchors.fill: parent
color: pressed ? qgcPal.buttonHighlightText : qgcPal.buttonText
horizontalAlignment: Text.AlignHCenter
verticalAlignment: Text.AlignVCenter
text: modelData
}
}
FactComboBox {
id: mainJSButtonActionCombo
width: ScreenTools.defaultFontPixelWidth * 15
fact: controller.parameterExists(-1, "BTN"+index+"_FUNCTION") ? controller.getParameterFact(-1, "BTN" + index + "_FUNCTION") : null;
indexModel: false
}
FactComboBox {
id: shiftJSButtonActionCombo
width: ScreenTools.defaultFontPixelWidth * 15
fact: controller.parameterExists(-1, "BTN"+index+"_SFUNCTION") ? controller.getParameterFact(-1, "BTN" + index + "_SFUNCTION") : null;
indexModel: false
}
}
}
}
}
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
......@@ -509,7 +509,7 @@ void MockLink::_handleManualControl(const mavlink_message_t& msg)
mavlink_manual_control_t manualControl;
mavlink_msg_manual_control_decode(&msg, &manualControl);
qDebug() << "MANUAL_CONTROL" << manualControl.x << manualControl.y << manualControl.z << manualControl.r;
qCDebug(MockLinkLog) << "MANUAL_CONTROL" << manualControl.x << manualControl.y << manualControl.z << manualControl.r;
}
void MockLink::_setParamFloatUnionIntoMap(int componentId, const QString& paramName, float paramFloat)
......
......@@ -997,11 +997,11 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
} else if (joystickMode == Vehicle::JoystickModeRC) {
// Save the new manual control inputs
manualRollAngle = roll;
manualPitchAngle = pitch;
manualYawAngle = yaw;
manualThrust = thrust;
manualButtons = buttons;
manualRollAngle = roll;
manualPitchAngle = pitch;
manualYawAngle = yaw;
manualThrust = thrust;
manualButtons = buttons;
// Store scaling values for all 3 axes
const float axesScaling = 1.0 * 1000.0;
......@@ -1009,19 +1009,22 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
// Calculate the new commands for roll, pitch, yaw, and thrust
const float newRollCommand = roll * axesScaling;
// negate pitch value because pitch is negative for pitching forward but mavlink message argument is positive for forward
const float newPitchCommand = -pitch * axesScaling;
const float newYawCommand = yaw * axesScaling;
const float newPitchCommand = -pitch * axesScaling;
const float newYawCommand = yaw * axesScaling;
const float newThrustCommand = thrust * axesScaling;
//qDebug() << newRollCommand << newPitchCommand << newYawCommand << newThrustCommand;
// Send the MANUAL_COMMAND message
mavlink_msg_manual_control_pack_chan(mavlink->getSystemId(),
mavlink->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&message,
this->uasId,
newPitchCommand, newRollCommand, newThrustCommand, newYawCommand, buttons);
mavlink_msg_manual_control_pack_chan(
static_cast<uint8_t>(mavlink->getSystemId()),
static_cast<uint8_t>(mavlink->getComponentId()),
_vehicle->priorityLink()->mavlinkChannel(),
&message,
static_cast<uint8_t>(this->uasId),
static_cast<int16_t>(newPitchCommand),
static_cast<int16_t>(newRollCommand),
static_cast<int16_t>(newThrustCommand),
static_cast<int16_t>(newYawCommand),
buttons);
}
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), message);
......
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