Skip to content
Draft
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
209 changes: 134 additions & 75 deletions src/Joystick/Joystick.cc

Large diffs are not rendered by default.

26 changes: 19 additions & 7 deletions src/Joystick/Joystick.h
Original file line number Diff line number Diff line change
Expand Up @@ -83,7 +83,6 @@ class Joystick : public QThread
Q_PROPERTY(QStringList assignableActionTitles READ assignableActionTitles NOTIFY assignableActionsChanged)
Q_PROPERTY(QStringList buttonActions READ buttonActions NOTIFY buttonActionsChanged)
Q_PROPERTY(bool enableManualControlExtensions READ enableManualControlExtensions WRITE setEnableManualControlExtensions NOTIFY enableManualControlExtensionsChanged)

enum ButtonEvent_t {
BUTTON_UP,
BUTTON_DOWN,
Expand Down Expand Up @@ -188,6 +187,9 @@ class Joystick : public QThread
bool enableManualControlExtensions() const { return _enableManualControlExtensions; }
void setEnableManualControlExtensions(bool enable);

QBitArray getButtonStates() const;
QList<float> getAxisValues() const;

signals:
// The raw signals are only meant for use by calibration
void rawAxisValueChanged(int index, int value);
Expand All @@ -203,6 +205,8 @@ class Joystick : public QThread
void circleCorrectionChanged(bool circleCorrection);
void enableManualControlExtensionsChanged();
void axisValues(float roll, float pitch, float yaw, float throttle);
void axisValuesUpdated(QList<float> axisValues);
void dataUpdated(QList<float> axisValues, QBitArray buttons);
void axisFrequencyHzChanged();
void buttonFrequencyHzChanged();
void startContinuousZoom(int direction);
Expand Down Expand Up @@ -286,6 +290,7 @@ private slots:
QmlObjectListModel *_assignableButtonActions = nullptr;

bool _accumulator = false;
float _throttleAccumulator = 0.f;
bool _calibrated = false;
bool _calibrationMode = false;
bool _circleCorrection = true;
Expand All @@ -307,13 +312,20 @@ private slots:

static int _transmitterMode;

static constexpr float _defaultAxisFrequencyHz = 25.0f;
static constexpr float _defaultButtonFrequencyHz = 5.0f;
static constexpr float kMinAxisValue = -1.0f;
static constexpr float kMaxAxisValue = 1.0f;

static constexpr float kDefaultAxisFrequencyHz = 25.0f;
static constexpr float kDefaultButtonFrequencyHz = 5.0f;

// Arbitrary Limits
static constexpr float _minAxisFrequencyHz = 0.25f;
static constexpr float _maxAxisFrequencyHz = 200.0f;
static constexpr float _minButtonFrequencyHz = 0.25f;
static constexpr float _maxButtonFrequencyHz = 50.0f;
static constexpr float kMinAxisFrequencyHz = 0.25f;
static constexpr float kMaxAxisFrequencyHz = 200.0f;
static constexpr float kMinButtonFrequencyHz = 0.25f;
static constexpr float kMaxButtonFrequencyHz = 50.0f;

// for throttle to change from min to max it will take 1000ms
static constexpr float kAccumulatorMaxSlewRate = 1000.0f;

static constexpr const char *_rgFunctionSettingsKey[maxAxisFunction] = {
"RollAxis",
Expand Down
2 changes: 1 addition & 1 deletion src/Joystick/JoystickAndroid.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#include <QtCore/QJniEnvironment>
#include <QtCore/QJniObject>

QGC_LOGGING_CATEGORY(JoystickAndroidLog, "Joystick.joystickandroid")
QGC_LOGGING_CATEGORY(JoystickAndroidLog, "Joystick.JoystickAndroid")

QList<int> JoystickAndroid::_androidBtnList(_androidBtnListCount);
int JoystickAndroid::ACTION_DOWN = 0;
Expand Down
2 changes: 1 addition & 1 deletion src/Joystick/JoystickManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include <QtCore/QApplicationStatic>
#include <QtCore/QSettings>

QGC_LOGGING_CATEGORY(JoystickManagerLog, "Joystick.joystickmanager")
QGC_LOGGING_CATEGORY(JoystickManagerLog, "Joystick.JoystickManager")

Q_APPLICATION_STATIC(JoystickManager, _joystickManager);

Expand Down
2 changes: 1 addition & 1 deletion src/Joystick/JoystickSDL.cc
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include <SDL3/SDL.h>

QGC_LOGGING_CATEGORY(JoystickSDLLog, "Joystick.joysticksdl")
QGC_LOGGING_CATEGORY(JoystickSDLLog, "Joystick.JoystickSDL")

JoystickSDL::JoystickSDL(const QString &name, QList<int> gamepadAxes, QList<int> nonGamepadAxes, int buttonCount, int hatCount, int instanceId, bool isGamepad, QObject *parent)
: Joystick(name, gamepadAxes.length() + nonGamepadAxes.length(), buttonCount, hatCount, parent)
Expand Down
46 changes: 46 additions & 0 deletions src/MAVLink/MAVLinkMessages.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,46 @@
/****************************************************************************
*
* (c) 2009-2024 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.
*
****************************************************************************/

#include "MAVLinkMessages.h"
#include "QGCLoggingCategory.h"

QGC_LOGGING_CATEGORY(MAVLinkMessagesLog, "MAVLink.MAVLinkMessages")

namespace MAVLinkMessages
{

void ManualControl::sendManualControlMsg(int16_t x, int16_t y, int16_t z, int16_t r,
int16_t s, int16_t t,
int16_t aux1, int16_t aux2, int16_t aux3, int16_t aux4, int16_t aux5, int16_t aux6,
QBitArray buttons)
{
mavlink_manual_control_t manual_control{};
manual_control.x = x;
manual_control.y = y;
manual_control.z = z;
manual_control.r = r;

manual_control.s = s;
manual_control.t = t;
manual_control.aux1 = aux1;
manual_control.aux2 = aux2;
manual_control.aux3 = aux3;
manual_control.aux4 = aux4;
manual_control.aux5 = aux5;
manual_control.aux6 = aux6;

bool ok;
const quint32 buttonPressed = buttons.toUInt32(QSysInfo::Endian::LittleEndian, &ok);
if (ok) {
manual_control.buttons = static_cast<uint16_t>(buttonPressed);
manual_control.buttons2 = static_cast<uint16_t>((buttonPressed >> 16) & 0xFFFF);
}
}

} // namespace MAVLinkMessages
59 changes: 59 additions & 0 deletions src/MAVLink/MAVLinkMessages.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,59 @@
/****************************************************************************
*
* (c) 2009-2024 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.
*
****************************************************************************/

#pragma once

#include "MAVLinkLib.h"

#include <QtCore/QLoggingCategory>

Q_DECLARE_LOGGING_CATEGORY(QGCMAVLinkMessagesLog)

namespace MAVLinkMessages
{

class MAVLinkMessage
{
public:
MAVLinkMessage() = default;
~MAVLinkMessage() = default;

protected:
mavlink_message_t message;
}

class ManualControl : public MAVLinkMessage
{
public:
ManualControl() = default;

private:
int16_t x = INT16_MAX;
int16_t y = INT16_MAX;
int16_t z = INT16_MAX;
int16_t r = INT16_MAX;

QBitArray buttons{32};

QBitArray extensions{8};

int16_t s = 0;
int16_t t = 0;

int16_t aux1 = 0;
int16_t aux2 = 0;
int16_t aux3 = 0;
int16_t aux4 = 0;
int16_t aux5 = 0;
int16_t aux6 = 0;

mavlink_manual_control_t manual_control{};
};

}; // namespace MAVLinkMessages
Loading
Loading