UASInterface.h 28.5 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 "UASWaypointManager.h"
44
#include "QGCUASParamManager.h"
45
#include "RadioCalibration/RadioCalibrationData.h"
pixhawk's avatar
pixhawk committed
46

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

54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87
enum BatteryType
{
    NICD = 0,
    NIMH = 1,
    LIION = 2,
    LIPOLY = 3,
    LIFE = 4,
    AGZN = 5
}; ///< The type of battery used

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

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

    /* MANAGEMENT */

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

lm's avatar
lm committed
117 118 119
    virtual double getLocalX() const = 0;
    virtual double getLocalY() const = 0;
    virtual double getLocalZ() const = 0;
120
    virtual bool localPositionKnown() const = 0;
lm's avatar
lm committed
121

122 123 124
    virtual double getLatitude() const = 0;
    virtual double getLongitude() const = 0;
    virtual double getAltitude() const = 0;
125
    virtual bool globalPositionKnown() const = 0;
126

lm's avatar
lm committed
127 128 129 130
    virtual double getRoll() const = 0;
    virtual double getPitch() const = 0;
    virtual double getYaw() const = 0;

131 132
    virtual bool getSelected() const = 0;

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

146 147
    virtual bool isArmed() const = 0;

148 149 150
    /** @brief Set the airframe of this MAV */
    virtual int getAirframe() const = 0;

151
    /** @brief Get reference to the waypoint manager **/
152
    virtual UASWaypointManager* getWaypointManager(void) = 0;
153 154 155 156 157
    /** @brief Get reference to the param manager **/
    virtual QGCUASParamManager* getParamManager() const = 0;
    // TODO Will be removed
    /** @brief Set reference to the param manager **/
    virtual void setParamManager(QGCUASParamManager* manager) = 0;
158

pixhawk's avatar
pixhawk committed
159 160 161 162 163 164 165 166 167 168 169
    /* 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,
170 171
        COMM_FAIL = 4,
        COMM_TIMEDOUT = 5///< Communication link failed
pixhawk's avatar
pixhawk committed
172 173
    };

174 175
    enum Airframe {
        QGC_AIRFRAME_GENERIC = 0,
176 177 178 179 180 181 182 183
        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
184 185
        QGC_AIRFRAME_PTERYX,
        QGC_AIRFRAME_TRICOPTER,
186
        QGC_AIRFRAME_HEXCOPTER,
Lorenz Meier's avatar
Lorenz Meier committed
187 188 189
        QGC_AIRFRAME_X8,
        QGC_AIRFRAME_VIPER_2_0,
        QGC_AIRFRAME_CAMFLYER_Q,
190
        QGC_AIRFRAME_END_OF_ENUM
191
    };
pixhawk's avatar
pixhawk committed
192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209

    /**
         * @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.
     */
210
    static QColor getNextColor() {
pixhawk's avatar
pixhawk committed
211
        /* Create color map */
212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232
        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
233
        static int nextColor = -1;
234 235
        if(nextColor == 18){//if at the end of the list
            nextColor = -1;//go back to the beginning
pixhawk's avatar
pixhawk committed
236
        }
237 238 239
        nextColor++; 
        return colors[nextColor];//return the next color
   }
pixhawk's avatar
pixhawk committed
240

241 242
    /** @brief Get the type of the system (airplane, quadrotor, helicopter,..)*/
    virtual int getSystemType() = 0;
lm's avatar
lm committed
243
    virtual QString getSystemTypeName() = 0;
LM's avatar
LM committed
244 245
    /** @brief Get the type of the autopilot (PIXHAWK, APM, UDB, PPZ,..) */
    virtual int getAutopilotType() = 0;
lm's avatar
lm committed
246
    virtual QString getAutopilotTypeName() = 0;
LM's avatar
LM committed
247
    virtual void setAutopilotType(int apType) = 0;
248

LM's avatar
LM committed
249 250 251 252
    virtual QMap<int, QString> getComponents() = 0;

    QColor getColor()
    {
pixhawk's avatar
pixhawk committed
253 254 255 256 257
        return color;
    }

public slots:

258 259
    /** @brief Set a new name for the system */
    virtual void setUASName(const QString& name) = 0;
lm's avatar
lm committed
260 261
    /** @brief Execute command immediately **/
    virtual void executeCommand(MAV_CMD command) = 0;
262
    /** @brief Executes a command **/
263
    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;
264 265
    /** @brief Executes a command ack, with success boolean **/
    virtual void executeCommandAck(int num, bool success) = 0;
266

267 268 269
    /** @brief Selects the airframe */
    virtual void setAirframe(int airframe) = 0;

pixhawk's avatar
pixhawk committed
270 271 272
    /** @brief Launches the system/Liftof **/
    virtual void launch() = 0;
    /** @brief Set a new waypoint **/
pixhawk's avatar
pixhawk committed
273
    //virtual void setWaypoint(Waypoint* wp) = 0;
pixhawk's avatar
pixhawk committed
274
    /** @brief Set this waypoint as next waypoint to fly to */
pixhawk's avatar
pixhawk committed
275
    //virtual void setWaypointActive(int wp) = 0;
pixhawk's avatar
pixhawk committed
276 277
    /** @brief Order the robot to return home / to land on the runway **/
    virtual void home() = 0;
278 279
    /** @brief Order the robot to land **/
    virtual void land() = 0;
pixhawk's avatar
pixhawk committed
280 281 282 283
    /** @brief Halt the system */
    virtual void halt() = 0;
    /** @brief Start/continue the current robot action */
    virtual void go() = 0;
pixhawk's avatar
pixhawk committed
284
    /** @brief Set the current mode of operation */
pixhawk's avatar
pixhawk committed
285
    virtual void setMode(int mode) = 0;
pixhawk's avatar
pixhawk committed
286 287 288 289 290 291 292 293 294 295
    /** 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;
296 297 298 299 300 301 302
    /** @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;
303
    /** @brief Request the list of stored waypoints from the robot */
pixhawk's avatar
pixhawk committed
304
    //virtual void requestWaypoints() = 0;
305
    /** @brief Clear all existing waypoints on the robot */
pixhawk's avatar
pixhawk committed
306
    //virtual void clearWaypointList() = 0;
307 308
    /** @brief Set world frame origin at current GPS position */
    virtual void setLocalOriginAtCurrentGPSPosition() = 0;
309 310
    /** @brief Set world frame origin / home position at this GPS position */
    virtual void setHomePosition(double lat, double lon, double alt) = 0;
311 312
    /** @brief Request all onboard parameters of all components */
    virtual void requestParameters() = 0;
313
    /** @brief Request one specific onboard parameter */
314
    virtual void requestParameter(int component, const QString& parameter) = 0;
315
    /** @brief Write parameter to permanent storage */
316 317 318
    virtual void writeParametersToStorage() = 0;
    /** @brief Read parameter from permanent storage */
    virtual void readParametersFromStorage() = 0;
319 320 321 322 323 324
    /** @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
     */
325
    virtual void setParameter(const int component, const QString& id, const QVariant& value) = 0;
pixhawk's avatar
pixhawk committed
326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341

    /**
     * @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
342

343 344 345 346 347
    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
348
    //virtual void enableRawSensorFusionTransmission(int rate) = 0;
349 350 351 352
    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
353

pixhawk's avatar
pixhawk committed
354
    virtual void setLocalPositionSetpoint(float x, float y, float z, float yaw) = 0;
pixhawk's avatar
pixhawk committed
355 356 357 358 359 360
    virtual void setLocalPositionOffset(float x, float y, float z, float yaw) = 0;

    virtual void startRadioControlCalibration() = 0;
    virtual void startMagnetometerCalibration() = 0;
    virtual void startGyroscopeCalibration() = 0;
    virtual void startPressureCalibration() = 0;
pixhawk's avatar
pixhawk committed
361

362 363 364 365
    /** @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;
366

Lorenz Meier's avatar
Lorenz Meier committed
367
    /** @brief Send the full HIL state to the MAV */
Lorenz Meier's avatar
Lorenz Meier committed
368 369 370
    virtual void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollspeed,
                        float pitchspeed, float yawspeed, double lat, double lon, double alt,
                        float vx, float vy, float vz, float xacc, float yacc, float zacc) = 0;
Lorenz Meier's avatar
Lorenz Meier committed
371 372 373 374 375 376 377 378 379

    /** @brief RAW sensors for sensor HIL */
    virtual void sendHilSensors(quint64 time_us, float xacc, float yacc, float zacc, float rollspeed, float pitchspeed, float yawspeed,
                                        float xmag, float ymag, float zmag, float abs_pressure, float diff_pressure, float pressure_alt, float temperature, quint16 fields_changed) = 0;

    /** @brief Send raw GPS for sensor HIL */
    virtual void sendHilGps(quint64 time_us, double lat, double lon, double alt, int fix_type, float eph, float epv, float vel, float cog, int satellites) = 0;


pixhawk's avatar
pixhawk committed
380 381 382 383
protected:
    QColor color;

signals:
LM's avatar
LM committed
384
    /** @brief The robot state has changed */
pixhawk's avatar
pixhawk committed
385
    void statusChanged(int stateFlag);
LM's avatar
LM committed
386 387
    /** @brief A new component was detected or created */
    void componentCreated(int uas, int component, const QString& name);
pixhawk's avatar
pixhawk committed
388 389 390 391 392 393 394
    /** @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);
395 396 397
    /** @brief System has been removed / disconnected / shutdown cleanly, remove */
    void systemRemoved(UASInterface* uas);
    void systemRemoved();
398 399 400 401 402 403
    /**
     * @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
404
     * @param compid ID of the sending component
405 406 407
     * @param text the status text
     * @param severity The severity of the message, 0 for plain debug messages, 10 for very critical messages
     */
408 409 410 411

    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);

412
    /** @brief A text message from the system has been received */
413
    void textMessageReceived(int uasid, int componentid, int severity, QString text);
414 415 416

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

417 418 419 420 421 422 423
    /** @brief System is now armed */
    void armed();
    /** @brief System is now disarmed */
    void disarmed();
    /** @brief Arming mode changed */
    void armingChanged(bool armed);

424 425 426 427 428 429 430 431 432 433 434 435 436 437 438
    /**
     * @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
439 440 441 442
    /**
     * @brief Drop rate of communication link updated
     *
     * @param systemId id of the air system
443
     * @param receiveDrop drop rate of packets this MAV receives (sent from GCS or other MAVs)
lm's avatar
lm committed
444
     */
445
    void dropRateChanged(int systemId,  float receiveDrop);
pixhawk's avatar
pixhawk committed
446 447
    /** @brief Robot mode has changed */
    void modeChanged(int sysId, QString status, QString description);
448 449
    /** @brief Robot armed state has changed */
    void armingChanged(int sysId, QString armingState);
pixhawk's avatar
pixhawk committed
450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465
    /** @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();
466

pixhawk's avatar
pixhawk committed
467 468 469
    /** @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
470 471
      * the groundstation. The data here should be converted to human-readable values before being passed, so ideally
	  * SI units.
pixhawk's avatar
pixhawk committed
472 473 474
      *
      * @param uasId ID of this system
      * @param name name of the value, e.g. "battery voltage"
475
	  * @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
476 477 478
      * @param value the value that changed
      * @param msec the timestamp of the message, in milliseconds
      */
479 480 481 482 483 484 485 486
    void valueChanged(const int uasId, const QString& name, const QString& unit, const quint8 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const qint8 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const quint16 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const qint16 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const quint32 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const qint32 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const quint64 value, const quint64 msec);
    void valueChanged(const int uasId, const QString& name, const QString& unit, const qint64 value, const quint64 msec);
487
    void valueChanged(const int uasId, const QString& name, const QString& unit, const double value, const quint64 msec);
488
    void valueChanged(const int uasid, const QString& name, const QString& unit, const QVariant value,const quint64 msecs);
lm's avatar
lm committed
489

pixhawk's avatar
pixhawk committed
490 491 492 493 494
    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);
495 496
    void parameterChanged(int uas, int component, QString parameterName, QVariant value);
    void parameterChanged(int uas, int component, int parameterCount, int parameterId, QString parameterName, QVariant value);
497
    void patternDetected(int uasId, QString patternPath, float confidence, bool detected);
pixhawk's avatar
pixhawk committed
498
    void letterDetected(int uasId, QString letter, float confidence, bool detected);
pixhawk's avatar
pixhawk committed
499 500 501 502 503 504 505 506
    /**
     * @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
507
    void batteryChanged(UASInterface* uas, double voltage, double current, double percent, int seconds);
pixhawk's avatar
pixhawk committed
508 509 510 511 512
    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);
513
    void attitudeChanged(UASInterface*, int component, double roll, double pitch, double yaw, quint64 usec);
514
    void attitudeRotationRatesChanged(int uas, double rollrate, double pitchrate, double yawrate, quint64 usec);
pixhawk's avatar
pixhawk committed
515
    void attitudeThrustSetPointChanged(UASInterface*, double rollDesired, double pitchDesired, double yawDesired, double thrustDesired, quint64 usec);
516
    /** @brief The MAV set a new setpoint in the local (not body) NED X, Y, Z frame */
lm's avatar
lm committed
517
    void positionSetPointsChanged(int uasid, float xDesired, float yDesired, float zDesired, float yawDesired, quint64 usec);
518 519
    /** @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
520
    void localPositionChanged(UASInterface*, double x, double y, double z, quint64 usec);
521
    void localPositionChanged(UASInterface*, int component, double x, double y, double z, quint64 usec);
lm's avatar
lm committed
522
    void globalPositionChanged(UASInterface*, double lat, double lon, double alt, quint64 usec);
523
    void altitudeChanged(UASInterface*, AltitudeMeasurementSource source, double altitude, quint64 usec);
lm's avatar
lm committed
524 525
    /** @brief Update the status of one satellite used for localization */
    void gpsSatelliteStatusChanged(int uasid, int satid, float azimuth, float direction, float snr, bool used);
526 527 528 529 530 531 532 533 534 535

    // The horizontal speed (a scalar)
    void speedChanged(UASInterface*, SpeedMeasurementSource source, double speed, quint64 usec);
    // The vertical speed (a scalar)
    void climbRateChanged(UASInterface*, AltitudeMeasurementSource source, double speed, quint64 usec);
    // Consider adding a MAV_FRAME parameter to this; could help specifying what the 3 scalars are.
    void velocityChanged(UASInterface*, MAV_FRAME frame, double vx, double vy, double vz, quint64 usec);

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

pixhawk's avatar
pixhawk committed
536 537 538 539
    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);
540

pixhawk's avatar
pixhawk committed
541 542 543 544 545 546 547 548
    /** @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);
549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572
    /** @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);


573 574 575 576
    /** @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
577 578
    /** @brief Remote control RSSI changed */
    void remoteControlRSSIChanged(float rssi);
579 580
    /** @brief Radio Calibration Data has been received from the MAV*/
    void radioCalibrationReceived(const QPointer<RadioCalibrationData>&);
pixhawk's avatar
pixhawk committed
581

582 583 584 585 586 587 588 589 590 591 592 593 594
#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
595 596 597 598 599 600 601 602 603 604 605 606 607 608 609
    /**
     * @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);
610 611 612 613 614
    /**
     * @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);
615

616
    // ERROR AND STATUS SIGNALS
617 618
    /** @brief Heartbeat timed out or was regained */
    void heartbeatTimeout(bool timeout, unsigned int ms);
619 620
    /** @brief Name of system changed */
    void nameChanged(QString newName);
621 622
    /** @brief System has been selected as focused system */
    void systemSelected(bool selected);
623 624
    /** @brief Core specifications have changed */
    void systemSpecsChanged(int uasId);
625

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

629 630 631 632

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

633
protected:
634

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

pixhawk's avatar
pixhawk committed
638 639
};

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

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