FirmwarePlugin.h 11.5 KB
Newer Older
1 2 3 4 5 6 7 8 9
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/

Don Gagne's avatar
Don Gagne committed
10 11 12 13 14 15 16

/// @file
///     @author Don Gagne <don@thegagnes.com>

#ifndef FirmwarePlugin_H
#define FirmwarePlugin_H

Don Gagne's avatar
Don Gagne committed
17
#include "QGCMAVLink.h"
Don Gagne's avatar
Don Gagne committed
18 19
#include "VehicleComponent.h"
#include "AutoPilotPlugin.h"
20
#include "GeoFenceManager.h"
Don Gagne's avatar
Don Gagne committed
21 22 23 24

#include <QList>
#include <QString>

25 26
class Vehicle;

Don Gagne's avatar
Don Gagne committed
27 28
/// This is the base class for Firmware specific plugins
///
29 30 31 32
/// The FirmwarePlugin class represents the methods and objects which are specific to a certain Firmware flight stack.
/// This is the only place where flight stack specific code should reside in QGroundControl. The remainder of the
/// QGroundControl source is generic to a common mavlink implementation. The implementation in the base class supports
/// mavlink generic firmware. Override the base clase virtuals to create your own firmware specific plugin.
Don Gagne's avatar
Don Gagne committed
33

Don Gagne's avatar
Don Gagne committed
34
class FirmwarePlugin : public QObject
Don Gagne's avatar
Don Gagne committed
35 36 37 38 39 40
{
    Q_OBJECT

public:
    /// Set of optional capabilites which firmware may support
    typedef enum {
Don Gagne's avatar
Don Gagne committed
41 42 43
        SetFlightModeCapability =           1 << 0, ///< FirmwarePlugin::setFlightMode method is supported
        MavCmdPreflightStorageCapability =  1 << 1, ///< MAV_CMD_PREFLIGHT_STORAGE is supported
        PauseVehicleCapability =            1 << 2, ///< Vehicle supports pausing at current location
44 45
        GuidedModeCapability =              1 << 3, ///< Vehicle supports guided mode commands
        OrbitModeCapability =               1 << 4, ///< Vehicle supports orbit mode
Don Gagne's avatar
Don Gagne committed
46
    } FirmwareCapabilities;
47 48 49 50 51 52 53 54 55 56 57 58 59 60 61

    /// Maps from on parameter name to another
    ///     key:    parameter name to translate from
    ///     value:  mapped parameter name
    typedef QMap<QString, QString> remapParamNameMap_t;

    /// Maps from firmware minor version to remapParamNameMap_t entry
    ///     key:    firmware minor version
    ///     value:  remapParamNameMap_t entry
    typedef QMap<int, remapParamNameMap_t> remapParamNameMinorVersionRemapMap_t;

    /// Maps from firmware major version number to remapParamNameMinorVersionRemapMap_t entry
    ///     key:    firmware major version
    ///     value:  remapParamNameMinorVersionRemapMap_t entry
    typedef QMap<int, remapParamNameMinorVersionRemapMap_t> remapParamNameMajorVersionMap_t;
62

63
    /// Called when Vehicle is first created to perform any firmware specific setup.
Don Gagne's avatar
Don Gagne committed
64 65
    virtual void initializeVehicle(Vehicle* vehicle);

Don Gagne's avatar
Don Gagne committed
66
    /// @return true: Firmware supports all specified capabilites
67
    virtual bool isCapable(const Vehicle *vehicle, FirmwareCapabilities capabilities);
68

Don Gagne's avatar
Don Gagne committed
69 70 71 72
    /// Returns VehicleComponents for specified Vehicle
    ///     @param vehicle Vehicle  to associate with components
    /// @return List of VehicleComponents for the specified vehicle. Caller owns returned objects and must
    ///         free when no longer needed.
73
    virtual QList<VehicleComponent*> componentsForVehicle(AutoPilotPlugin* vehicle);
74

Don Gagne's avatar
Don Gagne committed
75
    /// Returns the list of available flight modes
Daniel Agar's avatar
Daniel Agar committed
76
    virtual QStringList flightModes(Vehicle* vehicle) {
77 78 79 80
        Q_UNUSED(vehicle);
        return QStringList();
    }

Don Gagne's avatar
Don Gagne committed
81 82 83
    /// Returns the name for this flight mode. Flight mode names must be human readable as well as audio speakable.
    ///     @param base_mode Base mode from mavlink HEARTBEAT message
    ///     @param custom_mode Custom mode from mavlink HEARTBEAT message
Don Gagne's avatar
Don Gagne committed
84
    virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode) const;
85

Don Gagne's avatar
Don Gagne committed
86 87 88
    /// Sets base_mode and custom_mode to specified flight mode.
    ///     @param[out] base_mode Base mode for SET_MODE mavlink message
    ///     @param[out] custom_mode Custom mode for SET_MODE mavlink message
89
    virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
Don Gagne's avatar
Don Gagne committed
90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113

    /// Returns whether the vehicle is in guided mode or not.
    virtual bool isGuidedMode(const Vehicle* vehicle) const;

    /// Set guided flight mode
    virtual void setGuidedMode(Vehicle* vehicle, bool guidedMode);

    /// Returns whether the vehicle is paused or not.
    virtual bool isPaused(const Vehicle* vehicle) const;

    /// Causes the vehicle to stop at current position. If guide mode is supported, vehicle will be let in guide mode.
    /// If not, vehicle will be left in Loiter.
    virtual void pauseVehicle(Vehicle* vehicle);

    /// Command vehicle to return to launch
    virtual void guidedModeRTL(Vehicle* vehicle);

    /// Command vehicle to land at current location
    virtual void guidedModeLand(Vehicle* vehicle);

    /// Command vehicle to takeoff from current location
    ///     @param altitudeRel Relative altitude to takeoff to
    virtual void guidedModeTakeoff(Vehicle* vehicle, double altitudeRel);

114 115 116 117
    /// Command vehicle to orbit given center point
    ///     @param centerCoord Center Coordinates
    virtual void guidedModeOrbit(Vehicle* vehicle, const QGeoCoordinate& centerCoord, double radius, double velocity, double altitude);

Don Gagne's avatar
Don Gagne committed
118 119 120 121 122 123
    /// Command vehicle to move to specified location (altitude is included and relative)
    virtual void guidedModeGotoLocation(Vehicle* vehicle, const QGeoCoordinate& gotoCoord);

    /// Command vehicle to change to the specified relatice altitude
    virtual void guidedModeChangeAltitude(Vehicle* vehicle, double altitudeRel);

124
    /// FIXME: This isn't quite correct being here. All code for Joystick suvehicleTypepport is currently firmware specific
Don Gagne's avatar
Don Gagne committed
125
    /// not just this. I'm going to try to change that. If not, this will need to be removed.
126 127 128 129
    /// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink
    /// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches.
    /// The remainder can be assigned to Vehicle actions.
    /// @return -1: reserver all buttons, >0 number of buttons to reserve
130
    virtual int manualControlReservedButtonCount(void);
131

132 133 134 135 136
    /// Returns true if the vehicle and firmware supports the use of a throttle joystick that
    /// is zero when centered. Typically not supported on vehicles that have bidirectional
    /// throttle.
    virtual bool supportsThrottleModeCenterZero(void);

137 138 139 140
    /// Returns true if the firmware supports the use of the MAVlink "MANUAL_CONTROL" message.
    /// By default, this returns false unless overridden in the firmware plugin.
    virtual bool supportsManualControl(void);

141 142 143 144
    /// Returns true if the firmware supports the use of the RC radio and requires the RC radio
    /// setup page. Returns true by default.
    virtual bool supportsRadio(void);

145 146 147 148
    /// Returns true if the firmware supports the AP_JSButton library, which allows joystick buttons
    /// to be assigned via parameters in firmware. Default is false.
    virtual bool supportsJSButton(void);

nopeppermint's avatar
nopeppermint committed
149
    /// Called before any mavlink message is processed by Vehicle such that the firmwre plugin
Don Gagne's avatar
Don Gagne committed
150 151
    /// can adjust any message characteristics. This is handy to adjust or differences in mavlink
    /// spec implementations such that the base code can remain mavlink generic.
152
    ///     @param vehicle Vehicle message came from
Don Gagne's avatar
Don Gagne committed
153
    ///     @param message[in,out] Mavlink message to adjust if needed.
154 155
    /// @return false: skip message, true: process message
    virtual bool adjustIncomingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);
156

Don Gagne's avatar
Don Gagne committed
157 158 159 160 161 162 163
    /// Called before any mavlink message is sent to the Vehicle so plugin can adjust any message characteristics.
    /// This is handy to adjust or differences in mavlink spec implementations such that the base code can remain
    /// mavlink generic.
    ///     @param vehicle Vehicle message came from
    ///     @param message[in,out] Mavlink message to adjust if needed.
    virtual void adjustOutgoingMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message);

164 165 166 167 168 169
    /// Determines how to handle the first item of the mission item list. Internally to QGC the first item
    /// is always the home position.
    /// @return
    ///     true: Send first mission item as home position to vehicle. When vehicle has no mission items on
    ///             it, it may or may not return a home position back in position 0.
    ///     false: Do not send first item to vehicle, sequence numbers must be adjusted
170
    virtual bool sendHomePositionToVehicle(void);
171

172
    /// Returns the parameter that is used to identify the default component
173 174 175 176 177 178 179 180 181 182 183 184
    virtual QString getDefaultComponentIdParam(void) const { return QString(); }

    /// Returns the parameter which is used to identify the version number of parameter set
    virtual QString getVersionParam(void) { return QString(); }

    /// Returns the parameter set version info pulled from inside the meta data file. -1 if not found.
    virtual void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion);

    /// Returns the internal resource parameter meta date file.
    virtual QString internalParameterMetaDataFile(void) { return QString(); }

    /// Loads the specified parameter meta data file.
Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
185
    /// @return Opaque parameter meta data information which must be stored with Vehicle. Vehicle is responsible to
186 187
    ///         call deleteParameterMetaData when no longer needed.
    virtual QObject* loadParameterMetaData(const QString& metaDataFile) { Q_UNUSED(metaDataFile); return NULL; }
188 189

    /// Adds the parameter meta data to the Fact
190 191
    ///     @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData
    virtual void addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) { Q_UNUSED(parameterMetaData); Q_UNUSED(fact); Q_UNUSED(vehicleType); return; }
Don Gagne's avatar
Don Gagne committed
192 193

    /// List of supported mission commands. Empty list for all commands supported.
194
    virtual QList<MAV_CMD> supportedMissionCommands(void);
195

196 197 198
    /// Returns the name of the mission command json override file for the specified vehicle type.
    ///     @param vehicleType Vehicle type to return file for, MAV_TYPE_GENERIC is a request for overrides for all vehicle types
    virtual QString missionCommandOverrides(MAV_TYPE vehicleType) const;
199

200 201 202 203 204
    /// Returns the mapping structure which is used to map from one parameter name to another based on firmware version.
    virtual const remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const;

    /// Returns the highest major version number that is known to the remap for this specified major version.
    virtual int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const;
Don Gagne's avatar
Don Gagne committed
205 206 207 208 209 210

    /// @return true: Motors are coaxial like an X8 config, false: Quadcopter for example
    virtual bool multiRotorCoaxialMotors(Vehicle* vehicle) { Q_UNUSED(vehicle); return false; }

    /// @return true: X confiuration, false: Plus configuration
    virtual bool multiRotorXConfig(Vehicle* vehicle) { Q_UNUSED(vehicle); return false; }
211 212 213 214 215 216 217 218

    /// Returns a newly create geofence manager for this vehicle. Returns NULL if this vehicle
    /// does not support geofence. You should make sense to check vehicle capabilites for geofence
    /// support.
    virtual GeoFenceManager* newGeoFenceManager(Vehicle* vehicle) { return new GeoFenceManager(vehicle); }

    /// Returns the parameter which holds the fence circle radius if supported.
    virtual QString geoFenceRadiusParam(Vehicle* vehicle) { Q_UNUSED(vehicle); return QString(); }
219 220 221

    /// Return the resource file which contains the set of params loaded for offline editing.
    virtual QString offlineEditingParamFile(Vehicle* vehicle) { Q_UNUSED(vehicle); return QString(); }
Don Gagne's avatar
Don Gagne committed
222 223 224
};

#endif