JoystickInput.cc 21 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18
/*=====================================================================
======================================================================*/

/**
 * @file
 *   @brief Joystick interface
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *   @author Andreas Romer <mavteam@student.ethz.ch>
 *
 */

#include "JoystickInput.h"

#include <QDebug>
#include <limits.h>
#include "UAS.h"
#include "UASManager.h"
19
#include "QGC.h"
20
#include <QMutexLocker>
Lorenz Meier's avatar
Lorenz Meier committed
21
#include <QSettings>
22
#include <math.h>
23 24 25
#include <limits>

using namespace std;
pixhawk's avatar
pixhawk committed
26 27 28 29 30 31

/**
 * The coordinate frame of the joystick axis is the aeronautical frame like shown on this image:
 * @image html http://pixhawk.ethz.ch/wiki/_media/standards/body-frame.png Aeronautical frame
 */
JoystickInput::JoystickInput() :
32 33
    sdlJoystickMin(-32768.0f),
    sdlJoystickMax(32767.0f),
34 35
    isEnabled(false),
    done(false),
36
    uas(NULL),
37 38
    autopilotType(0),
    systemType(0),
39
    uasCanReverse(false),
40 41 42 43 44 45
    rollAxis(-1),
    pitchAxis(-1),
    yawAxis(-1),
    throttleAxis(-1),
    joystickName(""),
    joystickID(-1),
46
    joystickNumButtons(0)
pixhawk's avatar
pixhawk committed
47
{
48

49 50 51 52 53
    for (int i = 0; i < 10; i++) {
        calibrationPositive[i] = sdlJoystickMax;
        calibrationNegative[i] = sdlJoystickMin;
    }

54 55
    // Make sure we initialize with the correct UAS.
    setActiveUAS(UASManager::instance()->getActiveUAS());
56

57 58
    // Start this thread. This allows the Joystick Settings window to work correctly even w/o any UASes connected.
    start();
pixhawk's avatar
pixhawk committed
59 60
}

61 62
JoystickInput::~JoystickInput()
{
63 64
    storeGeneralSettings();
    storeJoystickSettings();
LM's avatar
LM committed
65
    done = true;
Lorenz Meier's avatar
Lorenz Meier committed
66 67
}

68 69 70 71 72 73 74 75 76
void JoystickInput::loadGeneralSettings()
{
    // Load defaults from settings
    QSettings settings;
    settings.sync();

    // Deal with settings specific to the JoystickInput
    settings.beginGroup("JOYSTICK_INPUT");
    isEnabled = settings.value("ENABLED", false).toBool();
77
    joystickName = settings.value("JOYSTICK_NAME", "").toString();
78 79 80
    settings.endGroup();
}

81 82 83 84
/**
 * @brief Restores settings for the current joystick from saved settings file.
 * Assumes that both joystickName & joystickNumAxes are correct.
 */
85
void JoystickInput::loadJoystickSettings()
Lorenz Meier's avatar
Lorenz Meier committed
86
{
87 88 89
    // Load defaults from settings
    QSettings settings;
    settings.sync();
90 91

    // Now for the current joystick
92 93 94 95 96 97
    settings.beginGroup(joystickName);
    rollAxis = (settings.value("ROLL_AXIS_MAPPING", -1).toInt());
    pitchAxis = (settings.value("PITCH_AXIS_MAPPING", -1).toInt());
    yawAxis = (settings.value("YAW_AXIS_MAPPING", -1).toInt());
    throttleAxis = (settings.value("THROTTLE_AXIS_MAPPING", -1).toInt());

98 99 100 101
    // Clear out and then restore the (AUTOPILOT, SYSTEM) mapping for joystick settings
    joystickSettings.clear();
    int autopilots = settings.beginReadArray("AUTOPILOTS");
    for (int i = 0; i < autopilots; i++)
102
    {
103 104 105 106
        settings.setArrayIndex(i);
        int autopilotType = settings.value("AUTOPILOT_TYPE", 0).toInt();
        int systems = settings.beginReadArray("SYSTEMS");
        for (int j = 0; j < systems; j++)
107
        {
108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125
            settings.setArrayIndex(j);
            int systemType = settings.value("SYSTEM_TYPE", 0).toInt();

            // Now that both the autopilot and system type are available, update some references.
            QMap<int, bool>* joystickAxesInverted = &joystickSettings[autopilotType][systemType].axesInverted;
            QMap<int, bool>* joystickAxesLimited = &joystickSettings[autopilotType][systemType].axesLimited;
            QMap<int, int>* joystickButtonActions = &joystickSettings[autopilotType][systemType].buttonActions;

            // Read back the joystickAxesInverted QList one element at a time.
            int axesStored = settings.beginReadArray("AXES_INVERTED");
            for (int k = 0; k < axesStored; k++)
            {
                settings.setArrayIndex(k);
                int index = settings.value("INDEX", 0).toInt();
                bool inverted = settings.value("INVERTED", false).toBool();
                joystickAxesInverted->insert(index, inverted);
            }
            settings.endArray();
126

127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147
            // Read back the joystickAxesLimited QList one element at a time.
            axesStored = settings.beginReadArray("AXES_LIMITED");
            for (int k = 0; k < axesStored; k++)
            {
                settings.setArrayIndex(k);
                int index = settings.value("INDEX", 0).toInt();
                bool limited = settings.value("LIMITED", false).toBool();
                joystickAxesLimited->insert(index, limited);
            }
            settings.endArray();

            // Read back the button->action mapping.
            int buttonsStored = settings.beginReadArray("BUTTONS_ACTIONS");
            for (int k = 0; k < buttonsStored; k++)
            {
                settings.setArrayIndex(k);
                int index = settings.value("INDEX", 0).toInt();
                int action = settings.value("ACTION", 0).toInt();
                joystickButtonActions->insert(index, action);
            }
            settings.endArray();
148
        }
149
        settings.endArray();
150 151
    }
    settings.endArray();
152

153
    settings.endGroup();
154 155 156 157 158 159 160 161 162 163 164 165

    emit joystickSettingsChanged();
}

void JoystickInput::storeGeneralSettings() const
{
    QSettings settings;
    settings.beginGroup("JOYSTICK_INPUT");
    settings.setValue("ENABLED", isEnabled);
    settings.setValue("JOYSTICK_NAME", joystickName);
    settings.endGroup();
    settings.sync();
Lorenz Meier's avatar
Lorenz Meier committed
166 167
}

168
void JoystickInput::storeJoystickSettings() const
Lorenz Meier's avatar
Lorenz Meier committed
169
{
170 171 172 173 174 175 176
    // Store settings
    QSettings settings;
    settings.beginGroup(joystickName);
    settings.setValue("ROLL_AXIS_MAPPING", rollAxis);
    settings.setValue("PITCH_AXIS_MAPPING", pitchAxis);
    settings.setValue("YAW_AXIS_MAPPING", yawAxis);
    settings.setValue("THROTTLE_AXIS_MAPPING", throttleAxis);
177 178 179 180
    settings.beginWriteArray("AUTOPILOTS");
    QMapIterator<int, QMap<int, JoystickSettings> > i(joystickSettings);
    int autopilotIndex = 0;
    while (i.hasNext())
181
    {
182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253
        i.next();
        settings.setArrayIndex(autopilotIndex++);

        int autopilotType = i.key();
        settings.setValue("AUTOPILOT_TYPE", autopilotType);

        settings.beginWriteArray("SYSTEMS");
        QMapIterator<int, JoystickSettings> j(i.value());
        int systemIndex = 0;
        while (j.hasNext())
        {
            j.next();
            settings.setArrayIndex(systemIndex++);

            int systemType = j.key();
            settings.setValue("SYSTEM_TYPE", systemType);

            // Now that both the autopilot and system type are available, update some references.
            QMapIterator<int, bool> joystickAxesInverted(joystickSettings[autopilotType][systemType].axesInverted);
            QMapIterator<int, bool> joystickAxesLimited(joystickSettings[autopilotType][systemType].axesLimited);
            QMapIterator<int, int> joystickButtonActions(joystickSettings[autopilotType][systemType].buttonActions);

            settings.beginWriteArray("AXES_INVERTED");
            int k = 0;
            while (joystickAxesInverted.hasNext())
            {
                joystickAxesInverted.next();
                int inverted = joystickAxesInverted.value();
                // Only save this axes' inversion status if it's not the default
                if (inverted)
                {
                    settings.setArrayIndex(k++);
                    int index = joystickAxesInverted.key();
                    settings.setValue("INDEX", index);
                    settings.setValue("INVERTED", inverted);
                }
            }
            settings.endArray();

            settings.beginWriteArray("AXES_LIMITED");
            k = 0;
            while (joystickAxesLimited.hasNext())
            {
                joystickAxesLimited.next();
                int limited = joystickAxesLimited.value();
                if (limited)
                {
                    settings.setArrayIndex(k++);
                    int index = joystickAxesLimited.key();
                    settings.setValue("INDEX", index);
                    settings.setValue("LIMITED", limited);
                }
            }
            settings.endArray();

            settings.beginWriteArray("BUTTONS_ACTIONS");
            k = 0;
            while (joystickButtonActions.hasNext())
            {
                joystickButtonActions.next();
                int action = joystickButtonActions.value();
                if (action != -1)
                {
                    settings.setArrayIndex(k++);
                    int index = joystickButtonActions.key();
                    settings.setValue("INDEX", index);
                    settings.setValue("ACTION", action);
                }
            }
            settings.endArray();
        }
        settings.endArray(); // SYSTEMS
254
    }
255
    settings.endArray(); // AUTOPILOTS
256 257
    settings.endGroup();
    settings.sync();
258 259
}

pixhawk's avatar
pixhawk committed
260 261
void JoystickInput::setActiveUAS(UASInterface* uas)
{
262 263 264 265 266 267
    // Do nothing if the UAS hasn't changed.
    if (uas == this->uas)
    {
        return;
    }

pixhawk's avatar
pixhawk committed
268 269
    // Only connect / disconnect is the UAS is of a controllable UAS class
    UAS* tmp = 0;
LM's avatar
LM committed
270 271
    if (this->uas)
    {
pixhawk's avatar
pixhawk committed
272
        tmp = dynamic_cast<UAS*>(this->uas);
LM's avatar
LM committed
273 274
        if(tmp)
        {
275
            disconnect(this, SIGNAL(joystickChanged(float,float,float,float,qint8,qint8,quint16)), tmp, SLOT(setManualControlCommands(float,float,float,float,qint8,qint8,quint16)));
276
            disconnect(this, SIGNAL(actionTriggered(int)), tmp, SLOT(triggerAction(int)));
pixhawk's avatar
pixhawk committed
277
        }
278
        uasCanReverse = false;
pixhawk's avatar
pixhawk committed
279 280
    }

281 282 283 284 285 286
    // Save any settings for the last UAS
    if (joystickID > -1)
    {
        storeJoystickSettings();
    }

pixhawk's avatar
pixhawk committed
287 288
    this->uas = uas;

289
    if (this->uas && (tmp = dynamic_cast<UAS*>(this->uas)))
LM's avatar
LM committed
290
    {
291
        connect(this, SIGNAL(joystickChanged(float,float,float,float,qint8,qint8,quint16)), tmp, SLOT(setManualControlCommands(float,float,float,float,qint8,qint8,quint16)));
292 293 294 295 296 297 298 299
        connect(this, SIGNAL(actionTriggered(int)), tmp, SLOT(triggerAction(int)));
        uasCanReverse = tmp->systemCanReverse();

        // Update the joystick settings for a new UAS.
        autopilotType = uas->getAutopilotType();
        systemType = uas->getSystemType();
    }

300 301 302 303
    // Make sure any UI elements know we've updated the UAS. The UASManager signal is re-emitted here so that UI elements know to
    // update their UAS-specific UI.
    emit activeUASSet(uas);

304 305 306 307
    // Load any joystick-specific settings now that the UAS has changed.
    if (joystickID > -1)
    {
        loadJoystickSettings();
308
    }
pixhawk's avatar
pixhawk committed
309 310
}

311 312 313 314 315 316
void JoystickInput::setEnabled(bool enabled)
{
    this->isEnabled = enabled;
    storeJoystickSettings();
}

pixhawk's avatar
pixhawk committed
317 318
void JoystickInput::init()
{
319
    // Initialize SDL Joystick support and detect number of joysticks.
320
    if (SDL_InitSubSystem(SDL_INIT_JOYSTICK | SDL_INIT_NOPARACHUTE) < 0) {
pixhawk's avatar
pixhawk committed
321 322 323 324
        printf("Couldn't initialize SimpleDirectMediaLayer: %s\n", SDL_GetError());
    }

    // Enumerate joysticks and select one
325
    numJoysticks = SDL_NumJoysticks();
pixhawk's avatar
pixhawk committed
326

327 328 329
    // If no joysticks are connected, there's nothing we can do, so just keep
    // going back to sleep every second unless the program quits.
    while (!numJoysticks && !done)
LM's avatar
LM committed
330
    {
331
        QGC::SLEEP::sleep(1);
pixhawk's avatar
pixhawk committed
332
    }
333 334 335 336
    if (done)
    {
        return;
    }
pixhawk's avatar
pixhawk committed
337

338 339 340 341
    // Now that we've detected a joystick, load in the joystick-agnostic settings.
    loadGeneralSettings();

    // Enumerate all found devices
342
    qDebug() << QString("%1 Input devices found:").arg(numJoysticks);
343
    int activeJoystick = 0;
344
    for(int i=0; i < numJoysticks; i++ )
LM's avatar
LM committed
345
    {
346
        QString name = SDL_JoystickName(i);
347
        qDebug() << QString("\t%1").arg(name);
348 349 350 351 352 353 354 355

        // If we've matched this joystick to what was last opened, note it.
        // Note: The way this is implemented the LAST joystick of a given name will be opened.
        if (name == joystickName)
        {
            activeJoystick = i;
        }

356
        SDL_Joystick* x = SDL_JoystickOpen(i);
357 358
        qDebug() << QString("\tNumber of Axes: %1").arg(QString::number(SDL_JoystickNumAxes(x)));
        qDebug() << QString("\tNumber of Buttons: %1").arg(QString::number(SDL_JoystickNumButtons(x)));
359
        SDL_JoystickClose(x);
pixhawk's avatar
pixhawk committed
360 361
    }

362 363 364
    // Set the active joystick based on name, if a joystick was found in the saved settings, otherwise
    // default to the first one.
    setActiveJoystick(activeJoystick);
365

366
    // Now make sure we know what the current UAS is and track changes to it.
367
    setActiveUAS(UASManager::instance()->getActiveUAS());
368
    connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*)));
pixhawk's avatar
pixhawk committed
369
}
370

371 372 373 374
void JoystickInput::shutdown()
{
    done = true;
}
pixhawk's avatar
pixhawk committed
375 376 377

/**
 * @brief Execute the Joystick process
378 379
 * Note that the SDL procedure is polled. This is because connecting and disconnecting while the event checker is running
 * fails as of SDL 1.2. It is therefore much easier to just poll for the joystick we want to sample.
pixhawk's avatar
pixhawk committed
380 381 382 383 384
 */
void JoystickInput::run()
{
    init();

385
    forever
LM's avatar
LM committed
386 387 388
    {
        if (done)
        {
389 390 391
            done = false;
            exit();
            return;
LM's avatar
LM committed
392
        }
pixhawk's avatar
pixhawk committed
393

394 395
        // Poll the joystick for new values.
        SDL_JoystickUpdate();
pixhawk's avatar
pixhawk committed
396

397
        // Emit all necessary signals for all axes.
398
        for (int i = 0; i < joystickNumAxes; i++)
399 400 401
        {
            // First emit the uncalibrated values for each axis based on their ID.
            // This is generally not used for controlling a vehicle, but a UI representation, so it being slightly off is fine.
402
            // Here we map the joystick axis value into the initial range of [0:1].
403
            float axisValue = SDL_JoystickGetAxis(joystick, i);
404
            if (joystickSettings[autopilotType][systemType].axesInverted[i])
405
            {
406
                axisValue = (axisValue - calibrationNegative[i]) / (calibrationPositive[i] - calibrationNegative[i]);
407 408 409
            }
            else
            {
410
                axisValue = (axisValue - calibrationPositive[i]) / (calibrationNegative[i] - calibrationPositive[i]);
411
            }
412
            axisValue = 1.0f - axisValue;
413

414
            // For non-throttle axes or if the UAS can reverse, go ahead and convert this into the range [-1:1].
415
            if (uasCanReverse || throttleAxis != i)
416 417
            {
                axisValue = axisValue * 2.0f - 1.0f;
418
            }
419 420
            // Otherwise if this vehicle can only go forward, but the axis is limited to only the positive range,
            // scale this so the negative values are ignored for this axis and it's clamped to [0:1].
421
            else if (throttleAxis == i && joystickSettings[autopilotType][systemType].axesLimited.value(i))
422
            {
423
                axisValue = axisValue * 2.0f - 1.0f;
424 425 426 427
                if (axisValue < 0.0f)
                {
                    axisValue = 0.0f;
                }
428
            }
429 430 431 432

            // Bound rounding errors
            if (axisValue > 1.0f) axisValue = 1.0f;
            if (axisValue < -1.0f) axisValue = -1.0f;
433 434 435 436 437
            if (joystickAxes[i] != axisValue)
            {
                joystickAxes[i] = axisValue;
                emit axisValueChanged(i, axisValue);
            }
438
        }
pixhawk's avatar
pixhawk committed
439 440

        // Build up vectors describing the hat position
441
        int hatPosition = SDL_JoystickGetHat(joystick, 0);
442
        qint8 newYHat = 0;
443 444
        if ((SDL_HAT_UP & hatPosition) > 0) newYHat = 1;
        if ((SDL_HAT_DOWN & hatPosition) > 0) newYHat = -1;
445
        qint8 newXHat = 0;
446 447 448 449 450 451
        if ((SDL_HAT_LEFT & hatPosition) > 0) newXHat = -1;
        if ((SDL_HAT_RIGHT & hatPosition) > 0) newXHat = 1;
        if (newYHat != yHat || newXHat != xHat)
        {
            xHat = newXHat;
            yHat = newYHat;
452
            emit hatDirectionChanged(newXHat, newYHat);
453
        }
pixhawk's avatar
pixhawk committed
454

455
        // Emit signals for each button individually
456
        for (int i = 0; i < joystickNumButtons; i++)
LM's avatar
LM committed
457
        {
458
            // If the button was down, but now it's up, trigger a buttonPressed event
459
            quint16 lastButtonState = joystickButtons & (1 << i);
460
            if (SDL_JoystickGetButton(joystick, i) && !lastButtonState)
LM's avatar
LM committed
461
            {
pixhawk's avatar
pixhawk committed
462
                emit buttonPressed(i);
463
                joystickButtons |= 1 << i;
464 465 466 467
            }
            else if (!SDL_JoystickGetButton(joystick, i) && lastButtonState)
            {
                emit buttonReleased(i);
468 469 470 471
                if (isEnabled && joystickSettings[autopilotType][systemType].buttonActions.contains(i))
                {
                    emit actionTriggered(joystickSettings[autopilotType][systemType].buttonActions.value(i));
                }
472
                joystickButtons &= ~(1 << i);
pixhawk's avatar
pixhawk committed
473 474
            }
        }
475 476

        // Now signal an update for all UI together.
477 478
        if (isEnabled)
        {
479 480 481 482
            float roll = rollAxis > -1?joystickAxes[rollAxis]:numeric_limits<float>::quiet_NaN();
            float pitch = pitchAxis > -1?joystickAxes[pitchAxis]:numeric_limits<float>::quiet_NaN();
            float yaw = yawAxis > -1?joystickAxes[yawAxis]:numeric_limits<float>::quiet_NaN();
            float throttle = throttleAxis > -1?joystickAxes[throttleAxis]:numeric_limits<float>::quiet_NaN();
483
            emit joystickChanged(roll, pitch, yaw, throttle, xHat, yHat, joystickButtons);
484
        }
pixhawk's avatar
pixhawk committed
485

486 487
        // Sleep, update rate of joystick is approx. 50 Hz (1000 ms / 50 = 20 ms)
        QGC::SLEEP::msleep(20);
pixhawk's avatar
pixhawk committed
488 489
    }
}
490

491 492
void JoystickInput::setActiveJoystick(int id)
{
493
    // If we already had a joystick, close that one before opening a new one.
494 495
    if (joystick && SDL_JoystickOpened(joystickID))
    {
496
        storeJoystickSettings();
497 498 499 500 501
        SDL_JoystickClose(joystick);
        joystick = NULL;
        joystickID = -1;
    }

502
    joystickID = id;
503
    joystick = SDL_JoystickOpen(joystickID);
504
    if (joystick && SDL_JoystickOpened(joystickID))
505
    {
506
        // Update joystick configuration.
507
        joystickName = QString(SDL_JoystickName(joystickID));
508 509 510
        joystickNumButtons = SDL_JoystickNumButtons(joystick);
        joystickNumAxes = SDL_JoystickNumAxes(joystick);

511
        // Restore saved settings for this joystick.
512
        loadJoystickSettings();
513

514 515
        // Update cached joystick axes values.
        // Also emit any signals for currently-triggering events
516
        joystickAxes.clear();
517
        for (int i = 0; i < joystickNumAxes; i++)
518
        {
519
            joystickAxes.append(numeric_limits<float>::quiet_NaN());
520
        }
521 522 523

        // Update cached joystick button values.
        // Emit signals for any button events.
524 525 526 527 528 529
        joystickButtons = 0;
    }
    else
    {
        joystickNumButtons = 0;
        joystickNumAxes = 0;
530
    }
531

532 533 534
    // Specify that a new joystick has been selected, so that any UI elements can update.
    emit newJoystickSelected();
    // And then trigger an update of this new UI.
535
    emit joystickSettingsChanged();
536 537
}

538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570
void JoystickInput::setAxisMapping(int axis, JOYSTICK_INPUT_MAPPING newMapping)
{
    switch (newMapping)
    {
        case JOYSTICK_INPUT_MAPPING_ROLL:
            rollAxis = axis;
            break;
        case JOYSTICK_INPUT_MAPPING_PITCH:
            pitchAxis = axis;
            break;
        case JOYSTICK_INPUT_MAPPING_YAW:
            yawAxis = axis;
            break;
        case JOYSTICK_INPUT_MAPPING_THROTTLE:
            throttleAxis = axis;
            break;
        case JOYSTICK_INPUT_MAPPING_NONE:
        default:
            if (rollAxis == axis)
            {
                rollAxis = -1;
            }
            if (pitchAxis == axis)
            {
                pitchAxis = -1;
            }
            if (yawAxis == axis)
            {
                yawAxis = -1;
            }
            if (throttleAxis == axis)
            {
                throttleAxis = -1;
571
                joystickSettings[autopilotType][systemType].axesLimited.remove(axis);
572 573 574
            }
            break;
    }
575
    storeJoystickSettings();
576 577 578 579
}

void JoystickInput::setAxisInversion(int axis, bool inverted)
{
580
    if (axis < joystickNumAxes)
581
    {
582 583
        joystickSettings[autopilotType][systemType].axesInverted[axis] = inverted;
        storeJoystickSettings();
584 585 586
    }
}

587 588
void JoystickInput::setAxisRangeLimit(int axis, bool limitRange)
{
589
    if (axis < joystickNumAxes)
590
    {
591 592
        joystickSettings[autopilotType][systemType].axesLimited[axis] = limitRange;
        storeJoystickSettings();
593 594 595
    }
}

596
void JoystickInput::setButtonAction(int button, int action)
597
{
598
    if (button < joystickNumButtons)
599
    {
600 601 602 603 604 605 606 607 608 609
        joystickSettings[autopilotType][systemType].buttonActions[button] = action;
        storeJoystickSettings();
    }
}

float JoystickInput::getCurrentValueForAxis(int axis) const
{
    if (axis < joystickNumAxes)
    {
        return joystickAxes.at(axis);
610 611
    }
    return 0.0f;
612
}
613

614
bool JoystickInput::getInvertedForAxis(int axis) const
615
{
616
    if (axis < joystickNumAxes)
617
    {
618
        return joystickSettings[autopilotType][systemType].axesInverted.value(axis);
619 620 621 622
    }
    return false;
}

623
bool JoystickInput::getRangeLimitForAxis(int axis) const
624
{
625
    if (axis < joystickNumAxes)
626
    {
627
        return joystickSettings[autopilotType][systemType].axesLimited.value(axis);
628 629 630
    }
    return false;
}
631 632 633 634 635 636 637 638 639

int JoystickInput::getActionForButton(int button) const
{
    if (button < joystickNumButtons && joystickSettings[autopilotType][systemType].buttonActions.contains(button))
    {
        return joystickSettings[autopilotType][systemType].buttonActions.value(button);
    }
    return -1;
}