Commit 9923c3e6 authored by Jonathan's avatar Jonathan

Quick add of joystick buttons values in Mavlink manual control messages

parent 61264568
......@@ -101,7 +101,7 @@ void JoystickInput::setActiveUAS(UASInterface* uas)
tmp = dynamic_cast<UAS*>(this->uas);
if(tmp)
{
disconnect(this, SIGNAL(joystickChanged(double,double,double,double,int,int)), tmp, SLOT(setManualControlCommands(double,double,double,double)));
disconnect(this, SIGNAL(joystickChanged(double,double,double,double,int,int,int)), tmp, SLOT(setManualControlCommands(double,double,double,double,int,int,int)));
disconnect(this, SIGNAL(buttonPressed(int)), tmp, SLOT(receiveButton(int)));
}
}
......@@ -110,7 +110,7 @@ void JoystickInput::setActiveUAS(UASInterface* uas)
tmp = dynamic_cast<UAS*>(this->uas);
if(tmp) {
connect(this, SIGNAL(joystickChanged(double,double,double,double,int,int)), tmp, SLOT(setManualControlCommands(double,double,double,double)));
connect(this, SIGNAL(joystickChanged(double,double,double,double,int,int,int)), tmp, SLOT(setManualControlCommands(double,double,double,double,int,int,int)));
connect(this, SIGNAL(buttonPressed(int)), tmp, SLOT(receiveButton(int)));
}
if (!isRunning())
......@@ -163,7 +163,6 @@ void JoystickInput::init()
*/
void JoystickInput::run()
{
init();
forever
......@@ -284,16 +283,16 @@ void JoystickInput::run()
// Send new values to rest of groundstation
emit hatDirectionChanged(xHat, yHat);
emit joystickChanged(y, x, yaw, thrust, xHat, yHat);
// Display all buttons
int buttons = 0;
for(int i = 0; i < SDL_JoystickNumButtons(joystick); i++)
{
//qDebug() << "BUTTON" << i << "is: " << SDL_JoystickGetAxis(joystick, i);
if(SDL_JoystickGetButton(joystick, i))
{
emit buttonPressed(i);
buttons |= 1 << i;
// Check if button is a UAS select button
if (uasButtonList.contains(i))
......@@ -307,6 +306,7 @@ void JoystickInput::run()
}
}
emit joystickChanged(y, x, yaw, thrust, xHat, yHat, buttons);
// Sleep, update rate of joystick is approx. 50 Hz (1000 ms / 50 = 20 ms)
QGC::SLEEP::msleep(20);
......
......@@ -141,7 +141,7 @@ signals:
* @param xHat hat vector in forward-backward direction, +1 forward, 0 center, -1 backward
* @param yHat hat vector in left-right direction, -1 left, 0 center, +1 right
*/
void joystickChanged(double roll, double pitch, double yaw, double thrust, int xHat, int yHat);
void joystickChanged(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons);
/**
* @brief Thrust lever of the joystick has changed
......
......@@ -2435,7 +2435,7 @@ void UAS::disarmSystem()
* Set the manual control commands.
* This can only be done if the system has manual inputs enabled and is armed.
*/
void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust)
void UAS::setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons)
{
// Scale values
double rollPitchScaling = 1.0f * 1000.0f;
......
......@@ -566,7 +566,7 @@ public slots:
void disarmSystem();
/** @brief Set the values for the manual control of the vehicle */
void setManualControlCommands(double roll, double pitch, double yaw, double thrust);
void setManualControlCommands(double roll, double pitch, double yaw, double thrust, int xHat, int yHat, int buttons);
/** @brief Receive a button pressed event from an input device, e.g. joystick */
void receiveButton(int buttonIndex);
......
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