JoystickConfigController.h 9.75 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40
/*=====================================================================
 
 QGroundControl Open Source Ground Control Station
 
 (c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 
 This file is part of the QGROUNDCONTROL project
 
 QGROUNDCONTROL is free software: you can redistribute it and/or modify
 it under the terms of the GNU General Public License as published by
 the Free Software Foundation, either version 3 of the License, or
 (at your option) any later version.
 
 QGROUNDCONTROL is distributed in the hope that it will be useful,
 but WITHOUT ANY WARRANTY; without even the implied warranty of
 MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
 GNU General Public License for more details.
 
 You should have received a copy of the GNU General Public License
 along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
 
 ======================================================================*/


/// @file
///     @brief Radio Config Qml Controller
///     @author Don Gagne <don@thegagnes.com

#ifndef JoystickConfigController_H
#define JoystickConfigController_H

#include <QTimer>

#include "FactPanelController.h"
#include "QGCLoggingCategory.h"
#include "Joystick.h"

Q_DECLARE_LOGGING_CATEGORY(JoystickConfigControllerLog)

class RadioConfigest;
41
class JoystickManager;
42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125

namespace Ui {
    class JoystickConfigController;
}


class JoystickConfigController : public FactPanelController
{
    Q_OBJECT
    
    friend class RadioConfigTest; ///< This allows our unit test to access internal information needed.
    
public:
    JoystickConfigController(void);
    ~JoystickConfigController();
    
    Q_PROPERTY(QQuickItem* statusText   MEMBER _statusText)
    Q_PROPERTY(QQuickItem* cancelButton MEMBER _cancelButton)
    Q_PROPERTY(QQuickItem* nextButton   MEMBER _nextButton)
    Q_PROPERTY(QQuickItem* skipButton   MEMBER _skipButton)
    
    Q_PROPERTY(bool rollAxisMapped      READ rollAxisMapped     NOTIFY rollAxisMappedChanged)
    Q_PROPERTY(bool pitchAxisMapped     READ pitchAxisMapped    NOTIFY pitchAxisMappedChanged)
    Q_PROPERTY(bool yawAxisMapped       READ yawAxisMapped      NOTIFY yawAxisMappedChanged)
    Q_PROPERTY(bool throttleAxisMapped  READ throttleAxisMapped NOTIFY throttleAxisMappedChanged)
    
    Q_PROPERTY(int rollAxisValue        READ rollAxisValue      NOTIFY rollAxisValueChanged)
    Q_PROPERTY(int pitchAxisValue       READ pitchAxisValue     NOTIFY pitchAxisValueChanged)
    Q_PROPERTY(int yawAxisValue         READ yawAxisValue       NOTIFY yawAxisValueChanged)
    Q_PROPERTY(int throttleAxisValue    READ throttleAxisValue  NOTIFY throttleAxisValueChanged)
    
    Q_PROPERTY(int rollAxisReversed     READ rollAxisReversed       NOTIFY rollAxisReversedChanged)
    Q_PROPERTY(int pitchAxisReversed    READ pitchAxisReversed      NOTIFY pitchAxisReversedChanged)
    Q_PROPERTY(int yawAxisReversed      READ yawAxisReversed        NOTIFY yawAxisReversedChanged)
    Q_PROPERTY(int throttleAxisReversed READ throttleAxisReversed   NOTIFY throttleAxisReversedChanged)
    
    Q_PROPERTY(QString imageHelp MEMBER _imageHelp NOTIFY imageHelpChanged)
    
    Q_INVOKABLE void cancelButtonClicked(void);
    Q_INVOKABLE void skipButtonClicked(void);
    Q_INVOKABLE void nextButtonClicked(void);
    Q_INVOKABLE void start(void);
    
    int rollAxisValue(void);
    int pitchAxisValue(void);
    int yawAxisValue(void);
    int throttleAxisValue(void);
    
    bool rollAxisMapped(void);
    bool pitchAxisMapped(void);
    bool yawAxisMapped(void);
    bool throttleAxisMapped(void);
    
    bool rollAxisReversed(void);
    bool pitchAxisReversed(void);
    bool yawAxisReversed(void);
    bool throttleAxisReversed(void);
    
    int axisCount(void);
    
signals:
    void axisValueChanged(int axis, int value);
    
    void rollAxisMappedChanged(bool mapped);
    void pitchAxisMappedChanged(bool mapped);
    void yawAxisMappedChanged(bool mapped);
    void throttleAxisMappedChanged(bool mapped);
    
    void rollAxisValueChanged(int value);
    void pitchAxisValueChanged(int value);
    void yawAxisValueChanged(int value);
    void throttleAxisValueChanged(int value);
    
    void rollAxisReversedChanged(bool reversed);
    void pitchAxisReversedChanged(bool reversed);
    void yawAxisReversedChanged(bool reversed);
    void throttleAxisReversedChanged(bool reversed);
    
    void imageHelpChanged(QString source);
    
    // @brief Signalled when in unit test mode and a message box should be displayed by the next button
    void nextButtonMessageBoxDisplayed(void);

private slots:
126
    void _activeJoystickChanged(Joystick* joystick);
127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161
    void _axisValueChanged(int axis, int value);
   
private:
    /// @brief The states of the calibration state machine.
    enum calStates {
        calStateAxisWait,
        calStateBegin,
        calStateIdentify,
        calStateMinMax,
        calStateCenterThrottle,
        calStateDetectInversion,
        calStateTrims,
        calStateSave
    };
    
    typedef void (JoystickConfigController::*inputFn)(Joystick::AxisFunction_t function, int axis, int value);
    typedef void (JoystickConfigController::*buttonFn)(void);
    struct stateMachineEntry {
        Joystick::AxisFunction_t    function;
        const char*                 instructions;
        const char*                 image;
        inputFn                     rcInputFn;
        buttonFn                    nextFn;
        buttonFn                    skipFn;
    };
    
    /// @brief A set of information associated with a radio axis.
    struct AxisInfo {
        Joystick::AxisFunction_t    function;   ///< Function mapped to this axis, Joystick::maxFunction for none
        bool                        reversed;   ///< true: axis is reverse, false: not reversed
        int                         axisMin;    ///< Minimum axis value
        int                         axisMax;    ///< Maximum axis value
        int                         axisTrim;   ///< Trim position
    };
    
162 163
    Joystick* _activeJoystick;
    
164 165 166 167 168 169 170
    int _currentStep;  ///< Current step of state machine
    
    const struct stateMachineEntry* _getStateMachineEntry(int step);
    
    void _advanceState(void);
    void _setupCurrentState(void);
    
171 172
    bool _validAxis(int axis);

173 174 175 176 177 178 179 180 181 182 183
    void _inputCenterWaitBegin  (Joystick::AxisFunction_t function, int axis, int value);
    void _inputStickDetect      (Joystick::AxisFunction_t function, int axis, int value);
    void _inputStickMin         (Joystick::AxisFunction_t function, int axis, int value);
    void _inputCenterWait       (Joystick::AxisFunction_t function, int axis, int value);
    
    void _switchDetect(Joystick::AxisFunction_t function, int axis, int value, bool moveToNextStep);
    
    void _saveFlapsDown(void);
    void _skipFlaps(void);
    void _saveAllTrims(void);
    
Don Gagne's avatar
Don Gagne committed
184
    bool _stickSettleComplete(int axis, int value);
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
    
    void _validateCalibration(void);
    void _writeCalibration(void);
    void _resetInternalCalibrationValues(void);
    void _setInternalCalibrationValuesFromSettings(void);
    
    void _startCalibration(void);
    void _stopCalibration(void);
    void _calSave(void);

    void _calSaveCurrentValues(void);
    
    void _setHelpImage(const char* imageFile);
    
    void _signalAllAttiudeValueChanges(void);
    
    // Member variables

    static const char* _imageFileMode2Dir;
    static const char* _imageFilePrefix;
    static const char* _imageCenter;
    static const char* _imageThrottleUp;
    static const char* _imageThrottleDown;
    static const char* _imageYawLeft;
    static const char* _imageYawRight;
    static const char* _imageRollLeft;
    static const char* _imageRollRight;
    static const char* _imagePitchUp;
    static const char* _imagePitchDown;
    
    static const int _updateInterval;   ///< Interval for ui update timer
    
    int _rgFunctionAxisMapping[Joystick::maxFunction]; ///< Maps from joystick function to axis index. _axisMax indicates axis not set for this function.

    static const int _attitudeControls = 5;
    
221 222 223 224 225 226 227
    int                 _axisCount;         ///< Number of actual joystick axes available
    static const int    _axisNoAxis = -1;   ///< Signals no axis set
    static const int    _axisMinimum = 4;   ///< Minimum numner of joystick axes required to run PX4
    struct AxisInfo*    _rgAxisInfo;        ///< Information associated with each axis
    int*                _axisValueSave;     ///< Saved values prior to detecting axis movement
    int*                _axisRawValue;      ///< Current set of raw axis values

228 229 230 231 232 233 234 235 236 237 238 239 240 241
    enum calStates _calState;               ///< Current calibration state
    int     _calStateCurrentAxis;           ///< Current axis being worked on in calStateIdentify and calStateDetectInversion
    bool    _calStateAxisComplete;          ///< Work associated with current axis is complete
    int     _calStateIdentifyOldMapping;    ///< Previous mapping for axis being currently identified
    int     _calStateReverseOldMapping;     ///< Previous mapping for axis being currently used to detect inversion
    
    static const int _calCenterPoint;
    static const int _calValidMinValue;
    static const int _calValidMaxValue;
    static const int _calDefaultMinValue;
    static const int _calDefaultMaxValue;
    static const int _calRoughCenterDelta;
    static const int _calMoveDelta;
    static const int _calSettleDelta;
242
    static const int _calMinDelta;    
243 244 245 246 247 248 249 250 251 252 253 254 255 256
    
    int     _stickDetectAxis;
    int     _stickDetectInitialValue;
    int     _stickDetectValue;
    bool    _stickDetectSettleStarted;
    QTime   _stickDetectSettleElapsed;
    static const int _stickDetectSettleMSecs;
    
    QQuickItem* _statusText;
    QQuickItem* _cancelButton;
    QQuickItem* _nextButton;
    QQuickItem* _skipButton;
    
    QString _imageHelp;
257 258

    JoystickManager*    _joystickManager;
259 260 261
};

#endif // JoystickConfigController_H