ArduSubFirmwarePlugin.h 5.97 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
class APMSubmarineFactGroup : public FactGroup
{
    Q_OBJECT

public:
    APMSubmarineFactGroup(QObject* parent = NULL);

38 39 40 41 42 43 44 45 46 47 48 49 50 51 52
    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)
    Q_PROPERTY(Fact* inputHold           READ inputHold     CONSTANT)
    Q_PROPERTY(Fact* rangefinderDistance READ rangefinderDistance 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; }
    Fact* inputHold           (void) { return &_inputHoldFact; }
    Fact* rangefinderDistance (void) { return &_rangefinderDistanceFact; }
53 54 55 56 57 58

    static const char* _camTiltFactName;
    static const char* _tetherTurnsFactName;
    static const char* _lightsLevel1FactName;
    static const char* _lightsLevel2FactName;
    static const char* _pilotGainFactName;
59
    static const char* _inputHoldFactName;
60
    static const char* _rangefinderDistanceFactName;
61 62 63 64 65 66 67 68 69

    static const char* _settingsGroup;

private:
    Fact            _camTiltFact;
    Fact            _tetherTurnsFact;
    Fact            _lightsLevel1Fact;
    Fact            _lightsLevel2Fact;
    Fact            _pilotGainFact;
70
    Fact            _inputHoldFact;
71
    Fact            _rangefinderDistanceFact;
72
};
73 74 75 76 77 78

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

    APMSubMode(uint32_t mode, bool settable);
};

class ArduSubFirmwarePlugin : public APMFirmwarePlugin
{
    Q_OBJECT

public:
    ArduSubFirmwarePlugin(void);

DonLakeFlyer's avatar
DonLakeFlyer committed
111
    QList<MAV_CMD> supportedMissionCommands(void) final;
112

113 114
    int defaultJoystickTXMode(void) final { return 3; }

115 116
    void initializeStreamRates(Vehicle* vehicle) override final;

117 118
    bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities) final;

119
    bool supportsThrottleModeCenterZero(void) final;
120

121
    bool supportsRadio(void) final;
122

123
    bool supportsJSButton(void) final;
124

125
    bool supportsMotorInterference(void) final;
126

127
    /// Return the resource file which contains the vehicle icon used in the flight view when the view is dark (Satellite for instance)
128
    virtual QString vehicleImageOpaque(const Vehicle* vehicle) const final;
129 130

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

133 134
    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"); }
135 136
    const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; }
    int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const final;
137
    const QVariantList& toolBarIndicators(const Vehicle* vehicle) final;
138 139
    bool  adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) final;
    virtual QMap<QString, FactGroup*>* factGroups(void) final;
140
    void adjustMetaData(MAV_TYPE vehicleType, FactMetaData* metaData) override final;
141

142 143

private:
144
    QVariantList _toolBarIndicators;
145
    static bool _remapParamNameIntialized;
146
    QMap<QString, QString> _factRenameMap;
147
    static FirmwarePlugin::remapParamNameMajorVersionMap_t  _remapParamName;
148 149
    void _handleNamedValueFloat(mavlink_message_t* message);
    void _handleMavlinkMessage(mavlink_message_t* message);
150

151
    QMap<QString, FactGroup*> _nameToFactGroupMap;
152
    APMSubmarineFactGroup _infoFactGroup;
153
};
154
#endif