UASInterface.h 9.72 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (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.
 *
 ****************************************************************************/
pixhawk's avatar
pixhawk committed
9

Donald Gagne's avatar
Donald Gagne committed
10 11 12
// NO NEW CODE HERE
// UASInterface, UAS.h/cc are deprecated. All new functionality should go into Vehicle.h/cc
//
pixhawk's avatar
pixhawk committed
13 14 15 16 17 18 19 20

#ifndef _UASINTERFACE_H_
#define _UASINTERFACE_H_

#include <QObject>
#include <QList>
#include <QAction>
#include <QColor>
21
#include <QPointer>
pixhawk's avatar
pixhawk committed
22 23 24 25

#include "LinkInterface.h"
#include "ProtocolInterface.h"

26
#ifndef __mobile__
27
class FileManager;
28
#endif
29

pixhawk's avatar
pixhawk committed
30 31 32 33 34 35
/**
 * @brief Interface for all robots.
 *
 * This interface is abstract and thus cannot be instantiated. It serves only as type definition.
 * It represents an unmanned aerial vehicle, e.g. a micro air vehicle.
 **/
lm's avatar
lm committed
36 37
class UASInterface : public QObject
{
pixhawk's avatar
pixhawk committed
38 39 40 41 42 43
    Q_OBJECT
public:
    virtual ~UASInterface() {}

    /* MANAGEMENT */

44
    virtual int getUASID() const = 0; ///< Get the ID of the connected UAS
pixhawk's avatar
pixhawk committed
45
    /** @brief The time interval the robot is switched on **/
46
    virtual quint64 getUptime() const = 0;
pixhawk's avatar
pixhawk committed
47

lm's avatar
lm committed
48 49 50 51
    virtual double getRoll() const = 0;
    virtual double getPitch() const = 0;
    virtual double getYaw() const = 0;

52
#ifndef __mobile__
53
    virtual FileManager* getFileManager() = 0;
54
#endif
55

pixhawk's avatar
pixhawk committed
56 57 58 59 60 61 62 63
    /**
     * @brief Get the color for this UAS
     *
     * This static function holds a color map that allows to draw a new color for each robot
     *
     * @return The next color in the color map. The map holds 20 colors and starts from the beginning
     *         if the colors are exceeded.
     */
64
#if !defined(__mobile__)
65
    static QColor getNextColor() {
pixhawk's avatar
pixhawk committed
66
        /* Create color map */
67
        static QList<QColor> colors = QList<QColor>()
dogmaphobic's avatar
dogmaphobic committed
68 69 70 71 72 73 74 75
        << QColor(231,72,28)
        << QColor(104,64,240)
        << QColor(203,254,121)
        << QColor(161,252,116)
                << QColor(232,33,47)
        << QColor(116,251,110)
        << QColor(234,38,107)
        << QColor(104,250,138)
76
                << QColor(235,43,165)
dogmaphobic's avatar
dogmaphobic committed
77 78 79
        << QColor(98,248,176)
        << QColor(236,48,221)
        << QColor(92,247,217)
80
                << QColor(200,54,238)
dogmaphobic's avatar
dogmaphobic committed
81 82 83
        << QColor(87,231,246)
        << QColor(151,59,239)
        << QColor(81,183,244)
84
                << QColor(75,133,243)
dogmaphobic's avatar
dogmaphobic committed
85 86
        << QColor(242,255,128)
        << QColor(230,126,23);
87

pixhawk's avatar
pixhawk committed
88
        static int nextColor = -1;
89 90
        if(nextColor == 18){//if at the end of the list
            nextColor = -1;//go back to the beginning
pixhawk's avatar
pixhawk committed
91
        }
92
        nextColor++;
93 94
        return colors[nextColor];//return the next color
   }
95
#endif
pixhawk's avatar
pixhawk committed
96

LM's avatar
LM committed
97 98 99 100
    virtual QMap<int, QString> getComponents() = 0;

    QColor getColor()
    {
pixhawk's avatar
pixhawk committed
101 102 103
        return color;
    }

104 105 106 107 108
    enum StartCalibrationType {
        StartCalibrationRadio,
        StartCalibrationGyro,
        StartCalibrationMag,
        StartCalibrationAirspeed,
109
        StartCalibrationAccel,
110
        StartCalibrationLevel,
111
        StartCalibrationPressure,
Don Gagne's avatar
Don Gagne committed
112
        StartCalibrationEsc,
113
        StartCalibrationCopyTrims,
114 115
        StartCalibrationUavcanEsc,
        StartCalibrationCompassMot,
116 117 118
    };

    enum StartBusConfigType {
119 120
        StartBusConfigActuators,
        EndBusConfigActuators,
121
    };
dogmaphobic's avatar
dogmaphobic committed
122

123 124
    /// Starts the specified calibration
    virtual void startCalibration(StartCalibrationType calType) = 0;
dogmaphobic's avatar
dogmaphobic committed
125

126 127
    /// Ends any current calibration
    virtual void stopCalibration(void) = 0;
128

129 130 131 132 133 134
    /// Starts the specified bus configuration
    virtual void startBusConfig(StartBusConfigType calType) = 0;

    /// Ends any current bus configuration
    virtual void stopBusConfig(void) = 0;

pixhawk's avatar
pixhawk committed
135
public slots:
136 137
    /** @brief Order the robot to pair its receiver **/
    virtual void pairRX(int rxType, int rxSubType) = 0;
pixhawk's avatar
pixhawk committed
138

Lorenz Meier's avatar
Lorenz Meier committed
139
    /** @brief Send the full HIL state to the MAV */
dogmaphobic's avatar
dogmaphobic committed
140
#ifndef __mobile__
Lorenz Meier's avatar
Lorenz Meier committed
141 142
    virtual void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
                        float pitchspeed, float yawspeed, double lat, double lon, double alt,
143
                        float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc) = 0;
Lorenz Meier's avatar
Lorenz Meier committed
144 145 146

    /** @brief RAW sensors for sensor HIL */
    virtual void sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
147
                                float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, quint32 fields_changed) = 0;
Lorenz Meier's avatar
Lorenz Meier committed
148 149

    /** @brief Send raw GPS for sensor HIL */
150
    virtual void sendHilGps(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float vn, float ve, float vd, float cog, int satellites) = 0;
Lorenz Meier's avatar
Lorenz Meier committed
151

152 153 154
    /** @brief Send Optical Flow sensor message for HIL, (arguments and units accoding to mavlink documentation*/
    virtual void sendHilOpticalFlow(quint64 time_us, qint16 flow_x, qint16 flow_y, float flow_comp_m_x,
                            float flow_comp_m_y, quint8 quality, float ground_distance) = 0;
dogmaphobic's avatar
dogmaphobic committed
155
#endif
156

157
    /** @brief Send command to map a RC channel to a parameter */
158
    virtual void sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax) = 0;
159 160 161 162

    /** @brief Send command to disable all bindings/maps between RC and parameters */
    virtual void unsetRCToParameterMap() = 0;

pixhawk's avatar
pixhawk committed
163 164 165 166
protected:
    QColor color;

signals:
167
    /** @brief A text message from the system has been received */
168
    void textMessageReceived(int uasid, int componentid, int severity, QString text);
169

170 171 172
    /**
     * @brief Update the error count of a device
     *
Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
173
     * The error count indicates how many errors occurred during the use of a device.
174 175 176 177 178 179 180
     * Usually a random error from time to time is acceptable, e.g. through electromagnetic
     * interferences on device lines like I2C and SPI. A constantly and rapidly increasing
     * error count however can help to identify broken cables or misbehaving drivers.
     *
     * @param uasid System ID
     * @param component Name of the component, e.g. "IMU"
     * @param device Name of the device, e.g. "SPI0" or "I2C1"
Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
181
     * @param count Errors occurred since system startup
182 183 184
     */
    void errCountChanged(int uasid, QString component, QString device, int count);

pixhawk's avatar
pixhawk committed
185 186 187 188
    /** @brief The robot is connected **/
    void connected();
    /** @brief The robot is disconnected **/
    void disconnected();
189

pixhawk's avatar
pixhawk committed
190 191 192
    /** @brief A value of the robot has changed.
      *
      * Typically this is used to send lowlevel information like the battery voltage to the plotting facilities of
193
      * the groundstation. The data here should be converted to human-readable values before being passed, so ideally
dogmaphobic's avatar
dogmaphobic committed
194
      * SI units.
pixhawk's avatar
pixhawk committed
195 196 197
      *
      * @param uasId ID of this system
      * @param name name of the value, e.g. "battery voltage"
dogmaphobic's avatar
dogmaphobic committed
198
      * @param unit The units this variable is in as an abbreviation. For system-dependent (such as raw ADC values) use "raw", for bitfields use "bits", for true/false or on/off use "bool", for unitless values use "-".
pixhawk's avatar
pixhawk committed
199 200 201
      * @param value the value that changed
      * @param msec the timestamp of the message, in milliseconds
      */
202
    void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant &value,const quint64 msecs);
lm's avatar
lm committed
203

204
    void parameterUpdate(int uas, int component, QString parameterName, int parameterCount, int parameterId, int type, QVariant value);
Don Gagne's avatar
Don Gagne committed
205

pixhawk's avatar
pixhawk committed
206 207 208 209 210 211 212 213
    /**
     * @brief The battery status has been updated
     *
     * @param uas sending system
     * @param voltage battery voltage
     * @param percent remaining capacity in percent
     * @param seconds estimated remaining flight time in seconds
     */
dongfang's avatar
dongfang committed
214
    void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds);
pixhawk's avatar
pixhawk committed
215 216
    void statusChanged(UASInterface* uas, QString status);
    void attitudeChanged(UASInterface*, double roll, double pitch, double yaw, quint64 usec);
217
    void attitudeChanged(UASInterface*, int component, double roll, double pitch, double yaw, quint64 usec);
218

pixhawk's avatar
pixhawk committed
219 220
    void imageStarted(int imgid, int width, int height, int depth, int channels);
    void imageDataReceived(int imgid, const unsigned char* imageData, int length, int startIndex);
221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238

    /** @brief Optical flow status changed */
    void opticalFlowStatusChanged(bool supported, bool enabled, bool ok);
    /** @brief Vision based localization status changed */
    void visionLocalizationStatusChanged(bool supported, bool enabled, bool ok);
    /** @brief Infrared / Ultrasound status changed */
    void distanceSensorStatusChanged(bool supported, bool enabled, bool ok);
    /** @brief Gyroscope status changed */
    void gyroStatusChanged(bool supported, bool enabled, bool ok);
    /** @brief Accelerometer status changed */
    void accelStatusChanged(bool supported, bool enabled, bool ok);
    /** @brief Magnetometer status changed */
    void magSensorStatusChanged(bool supported, bool enabled, bool ok);
    /** @brief Barometer status changed */
    void baroStatusChanged(bool supported, bool enabled, bool ok);
    /** @brief Differential pressure / airspeed status changed */
    void airspeedStatusChanged(bool supported, bool enabled, bool ok);

239 240 241
    // ERROR AND STATUS SIGNALS
    /** @brief Name of system changed */
    void nameChanged(QString newName);
242 243
    /** @brief Core specifications have changed */
    void systemSpecsChanged(int uasId);
244

dogmaphobic's avatar
dogmaphobic committed
245 246 247
    // Log Download Signals
    void logEntry   (UASInterface* uas, uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num);
    void logData    (UASInterface* uas, uint32_t ofs, uint16_t id, uint8_t count, const uint8_t* data);
248

pixhawk's avatar
pixhawk committed
249 250
};

lm's avatar
lm committed
251
Q_DECLARE_INTERFACE(UASInterface, "org.qgroundcontrol/1.0")
252

pixhawk's avatar
pixhawk committed
253
#endif // _UASINTERFACE_H_