ArduSubFirmwarePlugin.h 5.24 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
/*=====================================================================

 QGroundControl Open Source Ground Control Station

 (c) 2009 - 2014 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
///     @author Rustom Jehangir <rusty@bluerobotics.com>

#ifndef ArduSubFirmwarePlugin_H
#define ArduSubFirmwarePlugin_H

#include "APMFirmwarePlugin.h"
31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64
class APMSubmarineFactGroup : public FactGroup
{
    Q_OBJECT

public:
    APMSubmarineFactGroup(QObject* parent = NULL);

    Q_PROPERTY(Fact* camTilt       READ camTilt       CONSTANT)
    Q_PROPERTY(Fact* tetherTurns   READ tetherTurns   CONSTANT)
    Q_PROPERTY(Fact* lightsLevel1  READ lightsLevel1  CONSTANT)
    Q_PROPERTY(Fact* lightsLevel2  READ lightsLevel2  CONSTANT)
    Q_PROPERTY(Fact* pilotGain     READ pilotGain     CONSTANT)

    Fact* camTilt       (void) { return &_camTiltFact; }
    Fact* tetherTurns   (void) { return &_tetherTurnsFact; }
    Fact* lightsLevel1  (void) { return &_lightsLevel1Fact; }
    Fact* lightsLevel2  (void) { return &_lightsLevel2Fact; }
    Fact* pilotGain     (void) { return &_pilotGainFact; }

    static const char* _camTiltFactName;
    static const char* _tetherTurnsFactName;
    static const char* _lightsLevel1FactName;
    static const char* _lightsLevel2FactName;
    static const char* _pilotGainFactName;

    static const char* _settingsGroup;

private:
    Fact            _camTiltFact;
    Fact            _tetherTurnsFact;
    Fact            _lightsLevel1Fact;
    Fact            _lightsLevel2Fact;
    Fact            _pilotGainFact;
};
65 66 67 68 69 70

class APMSubMode : public APMCustomMode
{
public:
    enum Mode {
        STABILIZE         = 0,   // Hold level position
dheideman's avatar
dheideman committed
71
        ACRO              = 1,   // Manual angular rate, throttle
72
        ALT_HOLD          = 2,   // Depth hold
dheideman's avatar
dheideman committed
73 74
        AUTO              = 3,   // Full auto to waypoint
        GUIDED            = 4,   // Full auto to coordinate/direction
75 76
        RESERVED_5        = 5,
        RESERVED_6        = 6,
dheideman's avatar
dheideman committed
77
        CIRCLE            = 7,   // Auto circling
78
        RESERVED_8        = 8,
dheideman's avatar
dheideman committed
79
        SURFACE           = 9,   // Auto return to surface
80 81 82 83 84 85
        RESERVED_10       = 10,
        RESERVED_11       = 11,
        RESERVED_12       = 12,
        RESERVED_13       = 13,
        RESERVED_14       = 14,
        RESERVED_15       = 15,
dheideman's avatar
dheideman committed
86
        POSHOLD           = 16,  // Hold position
87 88 89
        RESERVED_17       = 17,
        RESERVED_18       = 18,
        MANUAL            = 19
90
    };
91
    static const int modeCount = 20;
92 93 94 95 96 97 98 99 100 101 102

    APMSubMode(uint32_t mode, bool settable);
};

class ArduSubFirmwarePlugin : public APMFirmwarePlugin
{
    Q_OBJECT

public:
    ArduSubFirmwarePlugin(void);

103 104
    QList<MAV_CMD> supportedMissionCommands(void);

105
    // Overrides from FirmwarePlugin
106
    int manualControlReservedButtonCount(void) final;
107

108 109
    int defaultJoystickTXMode(void) final { return 3; }

110
    bool supportsThrottleModeCenterZero(void) final;
111

112
    bool supportsRadio(void) final;
113

114
    bool supportsJSButton(void) final;
115

116
    bool supportsMotorInterference(void) final;
117

118
    /// Return the resource file which contains the vehicle icon used in the flight view when the view is dark (Satellite for instance)
119
    virtual QString vehicleImageOpaque(const Vehicle* vehicle) const final;
120 121

    /// Return the resource file which contains the vehicle icon used in the flight view when the view is light (Map for instance)
122
    virtual QString vehicleImageOutline(const Vehicle* vehicle) const final;
123

124 125
    QString brandImageIndoor(const Vehicle* vehicle) const final{ Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImageSub"); }
    QString brandImageOutdoor(const Vehicle* vehicle) const final { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImageSub"); }
126 127
    const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; }
    int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const final;
128
    const QVariantList& toolBarIndicators(const Vehicle* vehicle) final;
129 130
    bool  adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
    virtual QMap<QString, FactGroup*>* factGroups(void) final;
131

132 133

private:
134
    QVariantList _toolBarIndicators;
135 136
    static bool _remapParamNameIntialized;
    static FirmwarePlugin::remapParamNameMajorVersionMap_t  _remapParamName;
137 138
    void _handleNamedValueFloat(mavlink_message_t* message);
    void _handleMavlinkMessage(mavlink_message_t* message);
139

140
    QMap<QString, FactGroup*> _nameToFactGroupMap;
141
    APMSubmarineFactGroup _infoFactGroup;
142
};
143
#endif