UASInterface.h 28.4 KB
Newer Older
pixhawk's avatar
pixhawk committed
1 2
/*=====================================================================

3
QGroundControl Open Source Ground Control Station
pixhawk's avatar
pixhawk committed
4

5
(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
pixhawk's avatar
pixhawk committed
6

7
This file is part of the QGROUNDCONTROL project
pixhawk's avatar
pixhawk committed
8

9
    QGROUNDCONTROL is free software: you can redistribute it and/or modify
pixhawk's avatar
pixhawk committed
10 11 12 13
    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.

14
    QGROUNDCONTROL is distributed in the hope that it will be useful,
pixhawk's avatar
pixhawk committed
15 16 17 18 19
    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
20
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
pixhawk's avatar
pixhawk committed
21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38

======================================================================*/

/**
 * @file
 *   @brief Abstract interface, represents one unmanned aerial vehicle
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#ifndef _UASINTERFACE_H_
#define _UASINTERFACE_H_

#include <QObject>
#include <QList>
#include <QAction>
#include <QColor>
39
#include <QPointer>
pixhawk's avatar
pixhawk committed
40 41 42

#include "LinkInterface.h"
#include "ProtocolInterface.h"
43
#include "UASParameterDataModel.h"
44
#include "UASWaypointManager.h"
45
#include "QGCUASParamManagerInterface.h"
46
#include "RadioCalibration/RadioCalibrationData.h"
pixhawk's avatar
pixhawk committed
47

48 49
#ifdef QGC_PROTOBUF_ENABLED
#include <tr1/memory>
50
#ifdef QGC_USE_PIXHAWK_MESSAGES
LM's avatar
LM committed
51
#include <pixhawk/pixhawk.pb.h>
52
#endif
53
#endif
54

55 56 57 58 59 60 61 62 63 64
enum BatteryType
{
    NICD = 0,
    NIMH = 1,
    LIION = 2,
    LIPOLY = 3,
    LIFE = 4,
    AGZN = 5
}; ///< The type of battery used

65
/*
66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88
enum SpeedMeasurementSource
{
    PRIMARY_SPEED = 0,          // ArduPlane: Measured airspeed or estimated airspeed. ArduCopter: Ground (XY) speed.
    GROUNDSPEED_BY_UAV = 1,     // Ground speed as reported by UAS
    GROUNDSPEED_BY_GPS = 2,     // Ground speed as calculated from received GPS velocity data
    LOCAL_SPEED = 3
}; ///< For velocity data, the data source

enum AltitudeMeasurementSource
{
    PRIMARY_ALTITUDE = 0,                  // ArduPlane: air and ground speed mix. This is the altitude used for navigastion.
    BAROMETRIC_ALTITUDE = 1,               // Altitude is pressure altitude. Ardupilot reports no altitude purely by barometer,
                                           // however when ALT_MIX==1, mix-altitude is purely barometric.
    GPS_ALTITUDE = 2                       // GPS ASL altitude
}; ///< For altitude data, the data source

// TODO!!! The different frames are probably represented elsewhere. There should really only
// be one set of frames. We also need to keep track of the home alt. somehow.
enum AltitudeMeasurementFrame
{
    ABSOLUTE = 0,               // Altitude is pressure altitude
    ABOVE_HOME_POSITION = 1
}; ///< For altitude data, a reference frame
89
*/
90

pixhawk's avatar
pixhawk committed
91 92 93 94 95 96
/**
 * @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
97 98
class UASInterface : public QObject
{
pixhawk's avatar
pixhawk committed
99 100 101 102 103 104 105
    Q_OBJECT
public:
    virtual ~UASInterface() {}

    /* MANAGEMENT */

    /** @brief The name of the robot **/
106
    virtual QString getUASName() const = 0;
107 108 109 110
    /** @brief Get short state */
    virtual const QString& getShortState() const = 0;
    /** @brief Get short mode */
    virtual const QString& getShortMode() const = 0;
111 112
    /** @brief Translate mode id into text */
    static QString getShortModeTextFor(int id);
pixhawk's avatar
pixhawk committed
113
    //virtual QColor getColor() = 0;
114
    virtual int getUASID() const = 0; ///< Get the ID of the connected UAS
pixhawk's avatar
pixhawk committed
115
    /** @brief The time interval the robot is switched on **/
116
    virtual quint64 getUptime() const = 0;
pixhawk's avatar
pixhawk committed
117
    /** @brief Get the status flag for the communication **/
118
    virtual int getCommunicationStatus() const = 0;
pixhawk's avatar
pixhawk committed
119

lm's avatar
lm committed
120 121 122
    virtual double getLocalX() const = 0;
    virtual double getLocalY() const = 0;
    virtual double getLocalZ() const = 0;
123
    virtual bool localPositionKnown() const = 0;
lm's avatar
lm committed
124

125 126
    virtual double getLatitude() const = 0;
    virtual double getLongitude() const = 0;
127 128
    virtual double getAltitudeAMSL() const = 0;
    virtual double getAltitudeRelative() const = 0;
129
    virtual bool globalPositionKnown() const = 0;
130

lm's avatar
lm committed
131 132 133 134
    virtual double getRoll() const = 0;
    virtual double getPitch() const = 0;
    virtual double getYaw() const = 0;

135 136
    virtual bool getSelected() const = 0;

137
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
138 139
    virtual px::GLOverlay getOverlay() = 0;
    virtual px::GLOverlay getOverlay(qreal& receivedTimestamp) = 0;
140 141 142 143
    virtual px::ObstacleList getObstacleList() = 0;
    virtual px::ObstacleList getObstacleList(qreal& receivedTimestamp) = 0;
    virtual px::Path getPath() = 0;
    virtual px::Path getPath(qreal& receivedTimestamp) = 0;
144 145 146 147
    virtual px::PointCloudXYZRGB getPointCloud() = 0;
    virtual px::PointCloudXYZRGB getPointCloud(qreal& receivedTimestamp) = 0;
    virtual px::RGBDImage getRGBDImage() = 0;
    virtual px::RGBDImage getRGBDImage(qreal& receivedTimestamp) = 0;
148 149
#endif

150 151
    virtual bool isArmed() const = 0;

152 153 154
    /** @brief Set the airframe of this MAV */
    virtual int getAirframe() const = 0;

155
    /** @brief Get reference to the waypoint manager **/
156
    virtual UASWaypointManager* getWaypointManager(void) = 0;
157

158
    /** @brief Get reference to the param manager **/
159
    virtual QGCUASParamManagerInterface* getParamManager() = 0;
160

pixhawk's avatar
pixhawk committed
161 162 163 164 165 166 167 168 169 170 171
    /* COMMUNICATION FLAGS */

    enum CommStatus {
        /** Unit is disconnected, no failure state reached so far **/
        COMM_DISCONNECTED = 0,
        /** The communication is established **/
        COMM_CONNECTING = 1,
        /** The communication link is up **/
        COMM_CONNECTED = 2,
        /** The connection is closed **/
        COMM_DISCONNECTING = 3,
172 173
        COMM_FAIL = 4,
        COMM_TIMEDOUT = 5///< Communication link failed
pixhawk's avatar
pixhawk committed
174 175
    };

176 177
    enum Airframe {
        QGC_AIRFRAME_GENERIC = 0,
178 179 180 181 182 183 184 185
        QGC_AIRFRAME_EASYSTAR,
        QGC_AIRFRAME_TWINSTAR,
        QGC_AIRFRAME_MERLIN,
        QGC_AIRFRAME_CHEETAH,
        QGC_AIRFRAME_MIKROKOPTER,
        QGC_AIRFRAME_REAPER,
        QGC_AIRFRAME_PREDATOR,
        QGC_AIRFRAME_COAXIAL,
lm's avatar
lm committed
186 187
        QGC_AIRFRAME_PTERYX,
        QGC_AIRFRAME_TRICOPTER,
188
        QGC_AIRFRAME_HEXCOPTER,
Lorenz Meier's avatar
Lorenz Meier committed
189 190 191
        QGC_AIRFRAME_X8,
        QGC_AIRFRAME_VIPER_2_0,
        QGC_AIRFRAME_CAMFLYER_Q,
192
        QGC_AIRFRAME_END_OF_ENUM
193
    };
pixhawk's avatar
pixhawk committed
194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211

    /**
         * @brief Get the links associated with this robot
         *
         * @return List with all links this robot is associated with. Association is usually
         *         based on the fact that a message for this robot has been received through that
         *         interface. The LinkInterface can support multiple protocols.
         **/
    virtual QList<LinkInterface*>* getLinks() = 0;

    /**
     * @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.
     */
212
    static QColor getNextColor() {
pixhawk's avatar
pixhawk committed
213
        /* Create color map */
214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234
        static QList<QColor> colors = QList<QColor>() 
		<< 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)
                << QColor(235,43,165) 
		<< QColor(98,248,176) 
		<< QColor(236,48,221) 
		<< QColor(92,247,217)
                << QColor(200,54,238) 
		<< QColor(87,231,246) 
		<< QColor(151,59,239) 
		<< QColor(81,183,244)
                << QColor(75,133,243) 
		<< QColor(242,255,128) 
		<< QColor(230,126,23);
        
pixhawk's avatar
pixhawk committed
235
        static int nextColor = -1;
236 237
        if(nextColor == 18){//if at the end of the list
            nextColor = -1;//go back to the beginning
pixhawk's avatar
pixhawk committed
238
        }
239 240 241
        nextColor++; 
        return colors[nextColor];//return the next color
   }
pixhawk's avatar
pixhawk committed
242

243 244
    /** @brief Get the type of the system (airplane, quadrotor, helicopter,..)*/
    virtual int getSystemType() = 0;
245 246 247 248 249
    /** @brief Indicates whether this system is capable of controlling a reverse velocity.
     * Used for, among other things, altering joystick input to either -1:1 or 0:1 range.
     */
    virtual bool systemCanReverse() const = 0;

lm's avatar
lm committed
250
    virtual QString getSystemTypeName() = 0;
LM's avatar
LM committed
251 252
    /** @brief Get the type of the autopilot (PIXHAWK, APM, UDB, PPZ,..) */
    virtual int getAutopilotType() = 0;
lm's avatar
lm committed
253
    virtual QString getAutopilotTypeName() = 0;
LM's avatar
LM committed
254
    virtual void setAutopilotType(int apType) = 0;
255

LM's avatar
LM committed
256 257 258 259
    virtual QMap<int, QString> getComponents() = 0;

    QColor getColor()
    {
pixhawk's avatar
pixhawk committed
260 261 262
        return color;
    }

263
    /** @brief Returns a list of actions/commands that this vehicle can perform.
264 265 266
     * Used for creating UI elements for built-in functionality for this vehicle.
     * Actions should be mappings to `void f(void);` functions that simply issue
     * a command to the vehicle.
267 268 269
     */
    virtual QList<QAction*> getActions() const = 0;

270 271 272
    static const unsigned int WAYPOINT_RADIUS_DEFAULT_FIXED_WING = 25;
    static const unsigned int WAYPOINT_RADIUS_DEFAULT_ROTARY_WING = 5;

pixhawk's avatar
pixhawk committed
273 274
public slots:

275 276
    /** @brief Set a new name for the system */
    virtual void setUASName(const QString& name) = 0;
lm's avatar
lm committed
277 278
    /** @brief Execute command immediately **/
    virtual void executeCommand(MAV_CMD command) = 0;
279
    /** @brief Executes a command **/
280
    virtual void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component) = 0;
281 282
    /** @brief Executes a command ack, with success boolean **/
    virtual void executeCommandAck(int num, bool success) = 0;
283

284 285 286
    /** @brief Selects the airframe */
    virtual void setAirframe(int airframe) = 0;

pixhawk's avatar
pixhawk committed
287 288 289
    /** @brief Launches the system/Liftof **/
    virtual void launch() = 0;
    /** @brief Set a new waypoint **/
pixhawk's avatar
pixhawk committed
290
    //virtual void setWaypoint(Waypoint* wp) = 0;
pixhawk's avatar
pixhawk committed
291
    /** @brief Set this waypoint as next waypoint to fly to */
pixhawk's avatar
pixhawk committed
292
    //virtual void setWaypointActive(int wp) = 0;
pixhawk's avatar
pixhawk committed
293 294
    /** @brief Order the robot to return home / to land on the runway **/
    virtual void home() = 0;
295 296
    /** @brief Order the robot to land **/
    virtual void land() = 0;
297 298
    /** @brief Order the robot to pair its receiver **/
    virtual void pairRX(int rxType, int rxSubType) = 0;
pixhawk's avatar
pixhawk committed
299 300 301 302
    /** @brief Halt the system */
    virtual void halt() = 0;
    /** @brief Start/continue the current robot action */
    virtual void go() = 0;
pixhawk's avatar
pixhawk committed
303
    /** @brief Set the current mode of operation */
304
    virtual void setMode(uint8_t newBaseMode, uint32_t newCustomMode) = 0;
pixhawk's avatar
pixhawk committed
305 306 307 308 309 310 311 312 313 314
    /** Stops the robot system. If it is an MAV, the robot starts the emergency landing procedure **/
    virtual void emergencySTOP() = 0;
    /** Kills the robot. All systems are immediately shut down (e.g. the main power line is cut). This might lead to a crash **/
    virtual bool emergencyKILL() = 0;
    /**
     * @brief Shut down the system's computers
     *
     * Works only if already landed and will cleanly shut down all onboard computers.
     */
    virtual void shutdown() = 0;
315 316 317 318 319 320 321
    /** @brief Set the target position for the robot to navigate to.
     *  @param x x-coordinate of the target position
     *  @param y y-coordinate of the target position
     *  @param z z-coordinate of the target position
     *  @param yaw heading of the target position
     */
    virtual void setTargetPosition(float x, float y, float z, float yaw) = 0;
322
    /** @brief Request the list of stored waypoints from the robot */
pixhawk's avatar
pixhawk committed
323
    //virtual void requestWaypoints() = 0;
324
    /** @brief Clear all existing waypoints on the robot */
pixhawk's avatar
pixhawk committed
325
    //virtual void clearWaypointList() = 0;
326 327
    /** @brief Set world frame origin at current GPS position */
    virtual void setLocalOriginAtCurrentGPSPosition() = 0;
328 329
    /** @brief Set world frame origin / home position at this GPS position */
    virtual void setHomePosition(double lat, double lon, double alt) = 0;
330 331
    /** @brief Request all onboard parameters of all components */
    virtual void requestParameters() = 0;
332
    /** @brief Request one specific onboard parameter */
333
    virtual void requestParameter(int component, const QString& parameter) = 0;
334
    /** @brief Write parameter to permanent storage */
335 336 337
    virtual void writeParametersToStorage() = 0;
    /** @brief Read parameter from permanent storage */
    virtual void readParametersFromStorage() = 0;
338 339 340 341 342 343
    /** @brief Set a system parameter
     * @param component ID of the system component to write the parameter to
     * @param id String identifying the parameter
     * @warning The length of the ID string is limited by the MAVLink format! Take care to not exceed it
     * @param value Value of the parameter, IEEE 754 single precision floating point
     */
344
    virtual void setParameter(const int component, const QString& id, const QVariant& value) = 0;
pixhawk's avatar
pixhawk committed
345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360

    /**
     * @brief Add a link to the list of current links
     *
     * Adding the link to the robot's internal link list will allow him so send its own messages
     * over all registered links. Usually a link is added once a message for this particular robot
     * has been received over a link, but adding could also be done manually.
     * @warning Not all links should be added to all robots by default, because else all robots will
     *          attempt to send over all links, typically choking wireless serial links.
     */
    virtual void addLink(LinkInterface* link) = 0;

    /**
     * @brief Set the current robot as focused in the user interface
     */
    virtual void setSelected() = 0;
lm's avatar
lm committed
361

362 363 364 365 366
    virtual void enableAllDataTransmission(int rate) = 0;
    virtual void enableRawSensorDataTransmission(int rate) = 0;
    virtual void enableExtendedSystemStatusTransmission(int rate) = 0;
    virtual void enableRCChannelDataTransmission(int rate) = 0;
    virtual void enableRawControllerDataTransmission(int rate) = 0;
lm's avatar
lm committed
367
    //virtual void enableRawSensorFusionTransmission(int rate) = 0;
368 369 370 371
    virtual void enablePositionTransmission(int rate) = 0;
    virtual void enableExtra1Transmission(int rate) = 0;
    virtual void enableExtra2Transmission(int rate) = 0;
    virtual void enableExtra3Transmission(int rate) = 0;
pixhawk's avatar
pixhawk committed
372

pixhawk's avatar
pixhawk committed
373
    virtual void setLocalPositionSetpoint(float x, float y, float z, float yaw) = 0;
pixhawk's avatar
pixhawk committed
374 375
    virtual void setLocalPositionOffset(float x, float y, float z, float yaw) = 0;

376
    virtual void startRadioControlCalibration(int param=1) = 0;
377
    virtual void endRadioControlCalibration() = 0;
pixhawk's avatar
pixhawk committed
378 379 380
    virtual void startMagnetometerCalibration() = 0;
    virtual void startGyroscopeCalibration() = 0;
    virtual void startPressureCalibration() = 0;
pixhawk's avatar
pixhawk committed
381

382 383 384 385 386
    /** @brief Return if this a rotary wing */
    virtual bool isRotaryWing() = 0;
    /** @brief Return if this is a fixed wing */
    virtual bool isFixedWing() = 0;

387 388 389 390
    /** @brief Set the current battery type and voltages */
    virtual void setBatterySpecs(const QString& specs) = 0;
    /** @brief Get the current battery type and specs */
    virtual QString getBatterySpecs() = 0;
391

Lorenz Meier's avatar
Lorenz Meier committed
392
    /** @brief Send the full HIL state to the MAV */
Lorenz Meier's avatar
Lorenz Meier committed
393 394
    virtual void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
                        float pitchspeed, float yawspeed, double lat, double lon, double alt,
395
                        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
396 397 398

    /** @brief RAW sensors for sensor HIL */
    virtual void sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
399
                                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
400 401

    /** @brief Send raw GPS for sensor HIL */
402
    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
403

pixhawk's avatar
pixhawk committed
404 405 406 407
protected:
    QColor color;

signals:
LM's avatar
LM committed
408
    /** @brief The robot state has changed */
pixhawk's avatar
pixhawk committed
409
    void statusChanged(int stateFlag);
LM's avatar
LM committed
410 411
    /** @brief A new component was detected or created */
    void componentCreated(int uas, int component, const QString& name);
pixhawk's avatar
pixhawk committed
412 413 414 415 416 417 418
    /** @brief The robot state has changed
     *
     * @param uas this robot
     * @param status short description of status, e.g. "connected"
     * @param description longer textual description. Should be however limited to a short text, e.g. 200 chars.
     */
    void statusChanged(UASInterface* uas, QString status, QString description);
419 420 421 422 423 424
    /**
     * @brief Received a plain text message from the robot
     * This signal should NOT be used for standard communication, but rather for VERY IMPORTANT
     * messages like critical errors.
     *
     * @param uasid ID of the sending system
425
     * @param compid ID of the sending component
426 427 428
     * @param text the status text
     * @param severity The severity of the message, 0 for plain debug messages, 10 for very critical messages
     */
429 430 431 432

    void poiFound(UASInterface* uas, int type, int colorIndex, QString message, float x, float y, float z);
    void poiConnectionFound(UASInterface* uas, int type, int colorIndex, QString message, float x1, float y1, float z1, float x2, float y2, float z2);

433
    /** @brief A text message from the system has been received */
434
    void textMessageReceived(int uasid, int componentid, int severity, QString text);
435 436 437

    void navModeChanged(int uasid, int mode, const QString& text);

438 439 440 441 442 443 444
    /** @brief System is now armed */
    void armed();
    /** @brief System is now disarmed */
    void disarmed();
    /** @brief Arming mode changed */
    void armingChanged(bool armed);

445 446 447 448 449 450 451 452 453 454 455 456 457 458 459
    /**
     * @brief Update the error count of a device
     *
     * The error count indicates how many errors occured during the use of a device.
     * 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"
     * @param count Errors occured since system startup
     */
    void errCountChanged(int uasid, QString component, QString device, int count);

lm's avatar
lm committed
460 461 462 463
    /**
     * @brief Drop rate of communication link updated
     *
     * @param systemId id of the air system
464
     * @param receiveDrop drop rate of packets this MAV receives (sent from GCS or other MAVs)
lm's avatar
lm committed
465
     */
466
    void dropRateChanged(int systemId,  float receiveDrop);
pixhawk's avatar
pixhawk committed
467 468
    /** @brief Robot mode has changed */
    void modeChanged(int sysId, QString status, QString description);
469 470
    /** @brief Robot armed state has changed */
    void armingChanged(int sysId, QString armingState);
pixhawk's avatar
pixhawk committed
471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486
    /** @brief A command has been issued **/
    void commandSent(int command);
    /** @brief The connection status has changed **/
    void connectionChanged(CommStatus connectionFlag);
    /** @brief The robot is connecting **/
    void connecting();
    /** @brief The robot is connected **/
    void connected();
    /** @brief The robot is disconnected **/
    void disconnected();
    /** @brief The robot is active **/
    void activated();
    /** @brief The robot is inactive **/
    void deactivated();
    /** @brief The robot is manually controlled **/
    void manualControl();
487

pixhawk's avatar
pixhawk committed
488 489 490
    /** @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
491 492
      * the groundstation. The data here should be converted to human-readable values before being passed, so ideally
	  * SI units.
pixhawk's avatar
pixhawk committed
493 494 495
      *
      * @param uasId ID of this system
      * @param name name of the value, e.g. "battery voltage"
496
	  * @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
497 498 499
      * @param value the value that changed
      * @param msec the timestamp of the message, in milliseconds
      */
500
    void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant &value,const quint64 msecs);
lm's avatar
lm committed
501

pixhawk's avatar
pixhawk committed
502 503 504 505 506
    void voltageChanged(int uasId, double voltage);
    void waypointUpdated(int uasId, int id, double x, double y, double z, double yaw, bool autocontinue, bool active);
    void waypointSelected(int uasId, int id);
    void waypointReached(UASInterface* uas, int id);
    void autoModeChanged(bool autoMode);
507 508
    void parameterChanged(int uas, int component, QString parameterName, QVariant value);
    void parameterChanged(int uas, int component, int parameterCount, int parameterId, QString parameterName, QVariant value);
509
    void patternDetected(int uasId, QString patternPath, float confidence, bool detected);
pixhawk's avatar
pixhawk committed
510
    void letterDetected(int uasId, QString letter, float confidence, bool detected);
pixhawk's avatar
pixhawk committed
511 512 513 514 515 516 517 518
    /**
     * @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
519
    void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds);
pixhawk's avatar
pixhawk committed
520 521 522 523 524
    void statusChanged(UASInterface* uas, QString status);
    void actuatorChanged(UASInterface*, int actId, double value);
    void thrustChanged(UASInterface*, double thrust);
    void heartbeat(UASInterface* uas);
    void attitudeChanged(UASInterface*, double roll, double pitch, double yaw, quint64 usec);
525
    void attitudeChanged(UASInterface*, int component, double roll, double pitch, double yaw, quint64 usec);
526
    void attitudeRotationRatesChanged(int uas, double rollrate, double pitchrate, double yawrate, quint64 usec);
pixhawk's avatar
pixhawk committed
527
    void attitudeThrustSetPointChanged(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec);
528
    /** @brief The MAV set a new setpoint in the local (not body) NED X, Y, Z frame */
lm's avatar
lm committed
529
    void positionSetPointsChanged(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec);
530 531
    /** @brief A user (or an autonomous mission or obstacle avoidance planner) requested to set a new setpoint */
    void userPositionSetPointsChanged(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired);
pixhawk's avatar
pixhawk committed
532
    void localPositionChanged(UASInterface*, double x, double y, double z, quint64 usec);
533
    void localPositionChanged(UASInterface*, int component, double x, double y, double z, quint64 usec);
lm's avatar
lm committed
534
    void globalPositionChanged(UASInterface*, double lat, double lon, double alt, quint64 usec);
535
    void altitudeChanged(UASInterface*, double altitudeAMSL, double altitudeRelative, double climbRate, quint64 usec);
lm's avatar
lm committed
536 537
    /** @brief Update the status of one satellite used for localization */
    void gpsSatelliteStatusChanged(int uasid, int satid, float azimuth, float direction, float snr, bool used);
538 539

    // The horizontal speed (a scalar)
540
    void speedChanged(UASInterface* uas, double groundSpeed, double airSpeed, quint64 usec);
541
    // Consider adding a MAV_FRAME parameter to this; could help specifying what the 3 scalars are.
542
    void velocityChanged_NED(UASInterface*, double vx, double vy, double vz, quint64 usec);
543 544 545

    void navigationControllerErrorsChanged(UASInterface*, double altitudeError, double speedError, double xtrackError);

pixhawk's avatar
pixhawk committed
546 547 548 549
    void imageStarted(int imgid, int width, int height, int depth, int channels);
    void imageDataReceived(int imgid, const unsigned char* imageData, int length, int startIndex);
    /** @brief Emit the new system type */
    void systemTypeSet(UASInterface* uas, unsigned int type);
550

pixhawk's avatar
pixhawk committed
551 552 553 554 555 556 557 558
    /** @brief Attitude control enabled/disabled */
    void attitudeControlEnabled(bool enabled);
    /** @brief Position 2D control enabled/disabled */
    void positionXYControlEnabled(bool enabled);
    /** @brief Altitude control enabled/disabled */
    void positionZControlEnabled(bool enabled);
    /** @brief Heading control enabled/disabled */
    void positionYawControlEnabled(bool enabled);
559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582
    /** @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);
    /** @brief Actuator status changed */
    void actuatorStatusChanged(bool supported, bool enabled, bool ok);
    /** @brief Laser scanner status changed */
    void laserStatusChanged(bool supported, bool enabled, bool ok);
    /** @brief Vicon / Leica Geotracker status changed */
    void groundTruthSensorStatusChanged(bool supported, bool enabled, bool ok);


583 584 585 586
    /** @brief Value of a remote control channel (raw) */
    void remoteControlChannelRawChanged(int channelId, float raw);
    /** @brief Value of a remote control channel (scaled)*/
    void remoteControlChannelScaledChanged(int channelId, float normalized);
pixhawk's avatar
pixhawk committed
587 588
    /** @brief Remote control RSSI changed */
    void remoteControlRSSIChanged(float rssi);
589 590
    /** @brief Radio Calibration Data has been received from the MAV*/
    void radioCalibrationReceived(const QPointer<RadioCalibrationData>&);
pixhawk's avatar
pixhawk committed
591

592 593 594 595 596 597 598 599 600 601 602 603 604
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
    /** @brief Overlay data has been changed */
    void overlayChanged(UASInterface* uas);
    /** @brief Obstacle list data has been changed */
    void obstacleListChanged(UASInterface* uas);
    /** @brief Path data has been changed */
    void pathChanged(UASInterface* uas);
    /** @brief Point cloud data has been changed */
    void pointCloudChanged(UASInterface* uas);
    /** @brief RGBD image data has been changed */
    void rgbdImageChanged(UASInterface* uas);
#endif

pixhawk's avatar
pixhawk committed
605 606 607 608 609 610 611 612 613 614 615 616 617 618 619
    /**
     * @brief Localization quality changed
     * @param fix 0: lost, 1: 2D local position hold, 2: 2D localization, 3: 3D localization
     */
    void localizationChanged(UASInterface* uas, int fix);
    /**
     * @brief GPS localization quality changed
     * @param fix 0: lost, 1: at least one satellite, but no GPS fix, 2: 2D localization, 3: 3D localization
     */
    void gpsLocalizationChanged(UASInterface* uas, int fix);
    /**
     * @brief Vision localization quality changed
     * @param fix 0: lost, 1: 2D local position hold, 2: 2D localization, 3: 3D localization
     */
    void visionLocalizationChanged(UASInterface* uas, int fix);
620 621 622 623 624
    /**
     * @brief IR/U localization quality changed
     * @param fix 0: No IR/Ultrasound sensor, N > 0: Found N active sensors
     */
    void irUltraSoundLocalizationChanged(UASInterface* uas, int fix);
625

626
    // ERROR AND STATUS SIGNALS
627 628
    /** @brief Heartbeat timed out or was regained */
    void heartbeatTimeout(bool timeout, unsigned int ms);
629 630
    /** @brief Name of system changed */
    void nameChanged(QString newName);
631 632
    /** @brief System has been selected as focused system */
    void systemSelected(bool selected);
633 634
    /** @brief Core specifications have changed */
    void systemSpecsChanged(int uasId);
635

LM's avatar
LM committed
636 637 638
    /** @brief Object detected */
    void objectDetected(unsigned int time, int id, int type, const QString& name, int quality, float bearing, float distance);

639 640 641 642

    // HOME POSITION / ORIGIN CHANGES
    void homePositionChanged(int uas, double lat, double lon, double alt);

643 644 645
    /** @brief The system received an unknown message, which it could not interpret */
    void unknownPacketReceived(int uas, int component, int messageid);

646
protected:
647

648
    // TIMEOUT CONSTANTS
Lorenz Meier's avatar
Lorenz Meier committed
649
    static const unsigned int timeoutIntervalHeartbeat = 3500 * 1000; ///< Heartbeat timeout is 2.5 seconds
650

pixhawk's avatar
pixhawk committed
651 652
};

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

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