Commit 9e1d9e95 authored by Thomas Gubler's avatar Thomas Gubler

make joystick changed signal work again

parent 1bb5779d
...@@ -323,7 +323,7 @@ void JoystickInput::setActiveUAS(UASInterface* uas) ...@@ -323,7 +323,7 @@ void JoystickInput::setActiveUAS(UASInterface* uas)
tmp = dynamic_cast<UAS*>(this->uas); tmp = dynamic_cast<UAS*>(this->uas);
if(tmp) 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))); disconnect(this, SIGNAL(actionTriggered(int)), tmp, SLOT(triggerAction(int)));
} }
uasCanReverse = false; uasCanReverse = false;
...@@ -339,7 +339,8 @@ void JoystickInput::setActiveUAS(UASInterface* uas) ...@@ -339,7 +339,8 @@ void JoystickInput::setActiveUAS(UASInterface* uas)
if (this->uas && (tmp = dynamic_cast<UAS*>(this->uas))) if (this->uas && (tmp = dynamic_cast<UAS*>(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))); connect(this, SIGNAL(actionTriggered(int)), tmp, SLOT(triggerAction(int)));
uasCanReverse = tmp->systemCanReverse(); uasCanReverse = tmp->systemCanReverse();
......
...@@ -96,8 +96,8 @@ public: ...@@ -96,8 +96,8 @@ public:
enum JOYSTICK_MODE enum JOYSTICK_MODE
{ {
JOYSTICK_MODE_ATTITUDE = 0, JOYSTICK_MODE_ATTITUDE = 0,
JOYSTICK_MODE_POSITION = 1, JOYSTICK_MODE_POSITION = 1,
JOYSTICK_MODE_FORCE = 2, JOYSTICK_MODE_FORCE = 2
}; };
/** /**
...@@ -253,7 +253,7 @@ signals: ...@@ -253,7 +253,7 @@ signals:
* @param yHat hat vector in left-right direction, -1 left, 0 center, +1 right * @param yHat hat vector in left-right direction, -1 left, 0 center, +1 right
* @param mode (setpoint type) see JOYSTICK_MODE enum * @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 * @brief Emit a new value for an axis
...@@ -366,7 +366,7 @@ public slots: ...@@ -366,7 +366,7 @@ public slots:
* @brief Specify which setpoints should be sent to the UAS when moving the joystick * @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 * @param newMode the mode (setpoint type) see the JOYSTICK_MODE enum
*/ */
void setMode(int newMode) void setMode(quint8 newMode)
{ {
mode = (JOYSTICK_MODE)newMode; mode = (JOYSTICK_MODE)newMode;
} }
......
...@@ -2933,7 +2933,7 @@ void UAS::toggleAutonomy() ...@@ -2933,7 +2933,7 @@ void UAS::toggleAutonomy()
* Set the manual control commands. * Set the manual control commands.
* This can only be done if the system has manual inputs enabled and is armed. * 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(xHat);
Q_UNUSED(yHat); Q_UNUSED(yHat);
...@@ -2978,6 +2978,7 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t ...@@ -2978,6 +2978,7 @@ void UAS::setExternalControlSetpoint(float roll, float pitch, float yaw, float t
manualButtons = buttons; manualButtons = buttons;
mavlink_message_t message; mavlink_message_t message;
qDebug() << "js mode" << joystickMode;
if (joystickMode == JoystickInput::JOYSTICK_MODE_ATTITUDE) if (joystickMode == JoystickInput::JOYSTICK_MODE_ATTITUDE)
{ {
......
...@@ -839,7 +839,7 @@ public slots: ...@@ -839,7 +839,7 @@ public slots:
void toggleAutonomy(); void toggleAutonomy();
/** @brief Set the values for the manual control of the vehicle */ /** @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 */ /** @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); void setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw);
......
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