From 9e1d9e9547bf33f7401c9e7a28d16d09f3625b2b Mon Sep 17 00:00:00 2001 From: Thomas Gubler Date: Thu, 17 Jul 2014 15:01:43 +0200 Subject: [PATCH] make joystick changed signal work again --- src/input/JoystickInput.cc | 5 +++-- src/input/JoystickInput.h | 8 ++++---- src/uas/UAS.cc | 3 ++- src/uas/UAS.h | 2 +- 4 files changed, 10 insertions(+), 8 deletions(-) diff --git a/src/input/JoystickInput.cc b/src/input/JoystickInput.cc index 95260cd495..a1f11f6b78 100644 --- a/src/input/JoystickInput.cc +++ b/src/input/JoystickInput.cc @@ -323,7 +323,7 @@ void JoystickInput::setActiveUAS(UASInterface* uas) tmp = dynamic_cast(this->uas); if(tmp) { - disconnect(this, SIGNAL(joystickChanged(float,float,float,float,qint8,qint8,quint16,JOYSTICK_MODE)), tmp, SLOT(setExternalControlSetpoint(float,float,float,float,qint8,qint8,quint16, JOYSTICK_MODE))); + disconnect(this, SIGNAL(joystickChanged(float,float,float,float,qint8,qint8,quint16,quint8)), tmp, SLOT(setExternalControlSetpoint(float,float,float,float,qint8,qint8,quint16,quint8))); disconnect(this, SIGNAL(actionTriggered(int)), tmp, SLOT(triggerAction(int))); } uasCanReverse = false; @@ -339,7 +339,8 @@ void JoystickInput::setActiveUAS(UASInterface* uas) if (this->uas && (tmp = dynamic_cast(this->uas))) { - connect(this, SIGNAL(joystickChanged(float,float,float,float,qint8,qint8,quint16,JOYSTICK_MODE)), tmp, SLOT(setExternalControlSetpoint(float,float,float,float,qint8,qint8,quint16,JOYSTICK_MODE))); + connect(this, SIGNAL(joystickChanged(float,float,float,float,qint8,qint8,quint16,quint8)), tmp, SLOT(setExternalControlSetpoint(float,float,float,float,qint8,qint8,quint16,quint8))); + qDebug() << "connected joystick"; connect(this, SIGNAL(actionTriggered(int)), tmp, SLOT(triggerAction(int))); uasCanReverse = tmp->systemCanReverse(); diff --git a/src/input/JoystickInput.h b/src/input/JoystickInput.h index 1f6548fd88..682ee8a36e 100644 --- a/src/input/JoystickInput.h +++ b/src/input/JoystickInput.h @@ -96,8 +96,8 @@ public: enum JOYSTICK_MODE { JOYSTICK_MODE_ATTITUDE = 0, - JOYSTICK_MODE_POSITION = 1, - JOYSTICK_MODE_FORCE = 2, + JOYSTICK_MODE_POSITION = 1, + JOYSTICK_MODE_FORCE = 2 }; /** @@ -253,7 +253,7 @@ signals: * @param yHat hat vector in left-right direction, -1 left, 0 center, +1 right * @param mode (setpoint type) see JOYSTICK_MODE enum */ - void joystickChanged(float roll, float pitch, float yaw, float throttle, qint8 xHat, qint8 yHat, quint16 buttons, JOYSTICK_MODE mode); + void joystickChanged(float roll, float pitch, float yaw, float throttle, qint8 xHat, qint8 yHat, quint16 buttons, quint8 mode); /** * @brief Emit a new value for an axis @@ -366,7 +366,7 @@ public slots: * @brief Specify which setpoints should be sent to the UAS when moving the joystick * @param newMode the mode (setpoint type) see the JOYSTICK_MODE enum */ - void setMode(int newMode) + void setMode(quint8 newMode) { mode = (JOYSTICK_MODE)newMode; } diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index c3b0bdca26..fe729d9601 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -2933,7 +2933,7 @@ void UAS::toggleAutonomy() * Set the manual control commands. * This can only be done if the system has manual inputs enabled and is armed. */ -void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, qint8 xHat, qint8 yHat, quint16 buttons, JoystickInput::JOYSTICK_MODE joystickMode) +void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, qint8 xHat, qint8 yHat, quint16 buttons, quint8 joystickMode) { Q_UNUSED(xHat); Q_UNUSED(yHat); @@ -2978,6 +2978,7 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t manualButtons = buttons; mavlink_message_t message; + qDebug() << "js mode" << joystickMode; if (joystickMode == JoystickInput::JOYSTICK_MODE_ATTITUDE) { diff --git a/src/uas/UAS.h b/src/uas/UAS.h index de48cf9e4b..6c585576c3 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -839,7 +839,7 @@ public slots: void toggleAutonomy(); /** @brief Set the values for the manual control of the vehicle */ - void setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, qint8 xHat, qint8 yHat, quint16 buttons, JoystickInput::JOYSTICK_MODE joystickMode); + void setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, qint8 xHat, qint8 yHat, quint16 buttons, quint8); /** @brief Set the values for the 6dof manual control of the vehicle */ void setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw); -- GitLab