UAS.h 24.6 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38
/*=====================================================================

QGroundControl Open Source Ground Control Station

(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>

This file is part of the QGROUNDCONTROL project

    QGROUNDCONTROL is free software: you can redistribute it and/or modify
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

    QGROUNDCONTROL is distributed in the hope that it will be useful,
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.

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

/**
 * @file
 *   @brief Definition of Unmanned Aerial Vehicle object
 *
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

#ifndef _UAS_H_
#define _UAS_H_

#include "UASInterface.h"
#include <MAVLinkProtocol.h>
#include <QVector3D>
#include "QGCMAVLink.h"
39
#include "Vehicle.h"
40
#include "FirmwarePluginManager.h"
41

dogmaphobic's avatar
dogmaphobic committed
42
#ifndef __mobile__
43
#include "FileManager.h"
44 45
#include "QGCHilLink.h"
#include "QGCFlightGearLink.h"
46
#include "QGCJSBSimLink.h"
47
#include "QGCXPlaneLink.h"
dogmaphobic's avatar
dogmaphobic committed
48
#endif
49

50
Q_DECLARE_LOGGING_CATEGORY(UASLog)
tstellanova's avatar
tstellanova committed
51

52 53
class Vehicle;

54 55 56 57 58 59 60 61 62 63 64 65
/**
 * @brief A generic MAVLINK-connected MAV/UAV
 *
 * This class represents one vehicle. It can be used like the real vehicle, e.g. a call to halt()
 * will automatically send the appropriate messages to the vehicle. The vehicle state will also be
 * automatically updated by the comm architecture, so when writing code to e.g. control the vehicle
 * no knowledge of the communication infrastructure is needed.
 */
class UAS : public UASInterface
{
    Q_OBJECT
public:
66
    UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * firmwarePluginManager);
67

68 69
    float lipoFull;  ///< 100% charged voltage
    float lipoEmpty; ///< Discharged voltage
70 71 72 73 74 75 76 77 78 79 80

    /* MANAGEMENT */

    /** @brief Get the unique system id */
    int getUASID() const;
    /** @brief Get the components */
    QMap<int, QString> getComponents();

    /** @brief The time interval the robot is switched on */
    quint64 getUptime() const;
    /** @brief Add one measurement and get low-passed voltage */
81
    float filterVoltage(float value);
82

83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99
    Q_PROPERTY(double   latitude                READ getLatitude            WRITE setLatitude           NOTIFY latitudeChanged)
    Q_PROPERTY(double   longitude               READ getLongitude           WRITE setLongitude          NOTIFY longitudeChanged)
    Q_PROPERTY(double   satelliteCount          READ getSatelliteCount      WRITE setSatelliteCount     NOTIFY satelliteCountChanged)
    Q_PROPERTY(bool     isGlobalPositionKnown   READ globalPositionKnown)
    Q_PROPERTY(double   roll                    READ getRoll                WRITE setRoll               NOTIFY rollChanged)
    Q_PROPERTY(double   pitch                   READ getPitch               WRITE setPitch              NOTIFY pitchChanged)
    Q_PROPERTY(double   yaw                     READ getYaw                 WRITE setYaw                NOTIFY yawChanged)
    Q_PROPERTY(double   distToWaypoint          READ getDistToWaypoint      WRITE setDistToWaypoint     NOTIFY distToWaypointChanged)
    Q_PROPERTY(double   airSpeed                READ getGroundSpeed         WRITE setGroundSpeed        NOTIFY airSpeedChanged)
    Q_PROPERTY(double   groundSpeed             READ getGroundSpeed         WRITE setGroundSpeed        NOTIFY groundSpeedChanged)
    Q_PROPERTY(double   bearingToWaypoint       READ getBearingToWaypoint   WRITE setBearingToWaypoint  NOTIFY bearingToWaypointChanged)
    Q_PROPERTY(double   altitudeAMSL            READ getAltitudeAMSL        WRITE setAltitudeAMSL       NOTIFY altitudeAMSLChanged)
    Q_PROPERTY(double   altitudeAMSLFT          READ getAltitudeAMSLFT                                  NOTIFY altitudeAMSLFTChanged)
    Q_PROPERTY(double   altitudeRelative        READ getAltitudeRelative    WRITE setAltitudeRelative   NOTIFY altitudeRelativeChanged)
    Q_PROPERTY(double   satRawHDOP              READ getSatRawHDOP                                      NOTIFY satRawHDOPChanged)
    Q_PROPERTY(double   satRawVDOP              READ getSatRawVDOP                                      NOTIFY satRawVDOPChanged)
    Q_PROPERTY(double   satRawCOG               READ getSatRawCOG                                       NOTIFY satRawCOGChanged)
100

Don Gagne's avatar
Don Gagne committed
101 102
    /// Vehicle is about to go away
    void shutdownVehicle(void);
103

104 105 106 107 108 109 110 111 112 113
    void setGroundSpeed(double val)
    {
        groundSpeed = val;
        emit groundSpeedChanged(val,"groundSpeed");
        emit valueChanged(this->uasId,"groundSpeed","m/s",QVariant(val),getUnixTime());
    }
    double getGroundSpeed() const
    {
        return groundSpeed;
    }
114

115 116 117 118 119 120 121 122 123 124 125
    void setAirSpeed(double val)
    {
        airSpeed = val;
        emit airSpeedChanged(val,"airSpeed");
        emit valueChanged(this->uasId,"airSpeed","m/s",QVariant(val),getUnixTime());
    }

    double getAirSpeed() const
    {
        return airSpeed;
    }
126 127 128 129 130

    void setLocalX(double val)
    {
        localX = val;
        emit localXChanged(val,"localX");
131
        emit valueChanged(this->uasId,"localX","m",QVariant(val),getUnixTime());
132
    }
133

134 135 136 137
    double getLocalX() const
    {
        return localX;
    }
138 139 140 141 142

    void setLocalY(double val)
    {
        localY = val;
        emit localYChanged(val,"localY");
143
        emit valueChanged(this->uasId,"localY","m",QVariant(val),getUnixTime());
144
    }
145 146 147 148
    double getLocalY() const
    {
        return localY;
    }
149 150 151 152 153

    void setLocalZ(double val)
    {
        localZ = val;
        emit localZChanged(val,"localZ");
154
        emit valueChanged(this->uasId,"localZ","m",QVariant(val),getUnixTime());
155
    }
156 157 158 159
    double getLocalZ() const
    {
        return localZ;
    }
160 161 162 163 164

    void setLatitude(double val)
    {
        latitude = val;
        emit latitudeChanged(val,"latitude");
165
        emit valueChanged(this->uasId,"latitude","deg",QVariant(val),getUnixTime());
166
    }
167

168 169 170 171
    double getLatitude() const
    {
        return latitude;
    }
172 173 174 175 176

    void setLongitude(double val)
    {
        longitude = val;
        emit longitudeChanged(val,"longitude");
177
        emit valueChanged(this->uasId,"longitude","deg",QVariant(val),getUnixTime());
178
    }
179

180 181 182 183
    double getLongitude() const
    {
        return longitude;
    }
184

185
    void setAltitudeAMSL(double val)
186
    {
187 188
        altitudeAMSL = val;
        emit altitudeAMSLChanged(val, "altitudeAMSL");
189 190 191 192
        emit valueChanged(this->uasId,"altitudeAMSL","m",QVariant(altitudeAMSL),getUnixTime());
        altitudeAMSLFT = 3.28084 * altitudeAMSL;
        emit altitudeAMSLFTChanged(val, "altitudeAMSLFT");
        emit valueChanged(this->uasId,"altitudeAMSLFT","m",QVariant(altitudeAMSLFT),getUnixTime());
193 194
    }

195
    double getAltitudeAMSL() const
196
    {
197 198 199
        return altitudeAMSL;
    }

200 201 202 203 204
    double getAltitudeAMSLFT() const
    {
        return altitudeAMSLFT;
    }

205 206 207 208 209 210 211 212 213 214
    void setAltitudeRelative(double val)
    {
        altitudeRelative = val;
        emit altitudeRelativeChanged(val, "altitudeRelative");
        emit valueChanged(this->uasId,"altitudeRelative","m",QVariant(val),getUnixTime());
    }

    double getAltitudeRelative() const
    {
        return altitudeRelative;
215
    }
216

217 218 219 220 221 222 223 224 225 226 227 228 229 230 231
    double getSatRawHDOP() const
    {
        return satRawHDOP;
    }

    double getSatRawVDOP() const
    {
        return satRawVDOP;
    }

    double getSatRawCOG() const
    {
        return satRawCOG;
    }

232 233 234 235
    void setSatelliteCount(double val)
    {
        satelliteCount = val;
        emit satelliteCountChanged(val,"satelliteCount");
236
        emit valueChanged(this->uasId,"satelliteCount","",QVariant(val),getUnixTime());
237 238 239 240 241 242 243
    }

    double getSatelliteCount() const
    {
        return satelliteCount;
    }

244 245 246 247 248
    virtual bool globalPositionKnown() const
    {
        return isGlobalPositionKnown;
    }

249 250 251 252
    void setDistToWaypoint(double val)
    {
        distToWaypoint = val;
        emit distToWaypointChanged(val,"distToWaypoint");
253
        emit valueChanged(this->uasId,"distToWaypoint","m",QVariant(val),getUnixTime());
254 255 256 257 258 259 260
    }

    double getDistToWaypoint() const
    {
        return distToWaypoint;
    }

261 262 263 264
    void setBearingToWaypoint(double val)
    {
        bearingToWaypoint = val;
        emit bearingToWaypointChanged(val,"bearingToWaypoint");
265
        emit valueChanged(this->uasId,"bearingToWaypoint","deg",QVariant(val),getUnixTime());
266 267 268 269 270 271 272 273
    }

    double getBearingToWaypoint() const
    {
        return bearingToWaypoint;
    }


274 275 276 277 278 279
    void setRoll(double val)
    {
        roll = val;
        emit rollChanged(val,"roll");
    }

280 281 282 283
    double getRoll() const
    {
        return roll;
    }
284 285 286 287 288 289 290

    void setPitch(double val)
    {
        pitch = val;
        emit pitchChanged(val,"pitch");
    }

291 292 293 294
    double getPitch() const
    {
        return pitch;
    }
295 296 297 298 299 300 301

    void setYaw(double val)
    {
        yaw = val;
        emit yawChanged(val,"yaw");
    }

302 303 304 305
    double getYaw() const
    {
        return yaw;
    }
306

307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359
    // Setters for HIL noise variance
    void setXaccVar(float var){
        xacc_var = var;
    }

    void setYaccVar(float var){
        yacc_var = var;
    }

    void setZaccVar(float var){
        zacc_var = var;
    }

    void setRollSpeedVar(float var){
        rollspeed_var = var;
    }

    void setPitchSpeedVar(float var){
        pitchspeed_var = var;
    }

    void setYawSpeedVar(float var){
        pitchspeed_var = var;
    }

    void setXmagVar(float var){
        xmag_var = var;
    }

    void setYmagVar(float var){
        ymag_var = var;
    }

    void setZmagVar(float var){
        zmag_var = var;
    }

    void setAbsPressureVar(float var){
        abs_pressure_var = var;
    }

    void setDiffPressureVar(float var){
        diff_pressure_var = var;
    }

    void setPressureAltVar(float var){
        pressure_alt_var = var;
    }

    void setTemperatureVar(float var){
        temperature_var = var;
    }

360
#ifndef __mobile__
361
    friend class FileManager;
362
#endif
363 364

protected: //COMMENTS FOR TEST UNIT
365
    /// LINK ID AND STATUS
366
    int uasId;                    ///< Unique system ID
367
    QMap<int, QString> components;///< IDs and names of all detected onboard components
368

369 370
    QList<int> unknownPackets;    ///< Packet IDs which are unknown and have been received
    MAVLinkProtocol* mavlink;     ///< Reference to the MAVLink instance
371 372
    float receiveDropRate;        ///< Percentage of packets that were dropped on the MAV's receiving link (from GCS and other MAVs)
    float sendDropRate;           ///< Percentage of packets that were not received from the MAV by the GCS
373

374
    /// BASIC UAS TYPE, NAME AND STATE
375
    uint8_t base_mode;                 ///< The current mode of the MAV
376 377
    uint32_t custom_mode;         ///< The current mode of the MAV
    int status;                   ///< The current status of the MAV
378

379 380
    // dongfang: This looks like a candidate for being moved off to a separate class.
    /// BATTERY / ENERGY
381 382 383 384 385 386 387
    float startVoltage;         ///< Voltage at system start
    float tickVoltage;          ///< Voltage where 0.1 V ticks are told
    float lastTickVoltageValue; ///< The last voltage where a tick was announced
    float tickLowpassVoltage;   ///< Lowpass-filtered voltage for the tick announcement
    float warnLevelPercent;     ///< Warning level, in percent
    double currentVoltage;      ///< Voltage currently measured
    float lpVoltage;            ///< Low-pass filtered voltage
dongfang's avatar
dongfang committed
388
    double currentCurrent;      ///< Battery current currently measured
389 390
    bool batteryRemainingEstimateEnabled; ///< If the estimate is enabled, QGC will try to estimate the remaining battery life
    float chargeLevel;          ///< Charge level of battery, in percent
391 392 393 394 395
    bool lowBattAlarm;          ///< Switch if battery is low


    /// TIMEKEEPING
    quint64 startTime;            ///< The time the UAS was switched on
396 397
    quint64 onboardTimeOffset;

398
    /// MANUAL CONTROL
399 400 401 402 403 404 405 406 407
    bool controlRollManual;     ///< status flag, true if roll is controlled manually
    bool controlPitchManual;    ///< status flag, true if pitch is controlled manually
    bool controlYawManual;      ///< status flag, true if yaw is controlled manually
    bool controlThrustManual;   ///< status flag, true if thrust is controlled manually

    double manualRollAngle;     ///< Roll angle set by human pilot (radians)
    double manualPitchAngle;    ///< Pitch angle set by human pilot (radians)
    double manualYawAngle;      ///< Yaw angle set by human pilot (radians)
    double manualThrust;        ///< Thrust set by human pilot (radians)
408 409

    /// POSITION
410
    bool isGlobalPositionKnown; ///< If the global position has been received for this MAV
411

412 413 414
    double localX;
    double localY;
    double localZ;
415

416 417
    double latitude;            ///< Global latitude as estimated by position estimator
    double longitude;           ///< Global longitude as estimated by position estimator
418
    double altitudeAMSL;        ///< Global altitude as estimated by position estimator, AMSL
419
    double altitudeAMSLFT;      ///< Global altitude as estimated by position estimator, AMSL
420
    double altitudeRelative;    ///< Altitude above home as estimated by position estimator
421

422 423 424 425
    double satRawHDOP;
    double satRawVDOP;
    double satRawCOG;

426
    double satelliteCount;      ///< Number of satellites visible to raw GPS
427 428 429 430
    bool globalEstimatorActive; ///< Global position estimator present, do not fall back to GPS raw for position
    double latitude_gps;        ///< Global latitude as estimated by raw GPS
    double longitude_gps;       ///< Global longitude as estimated by raw GPS
    double altitude_gps;        ///< Global altitude as estimated by raw GPS
431 432 433
    double speedX;              ///< True speed in X axis
    double speedY;              ///< True speed in Y axis
    double speedZ;              ///< True speed in Z axis
434 435

    /// WAYPOINT NAVIGATION
436
    double distToWaypoint;       ///< Distance to next waypoint
437 438
    double airSpeed;             ///< Airspeed
    double groundSpeed;          ///< Groundspeed
439
    double bearingToWaypoint;    ///< Bearing to next waypoint
440
#ifndef __mobile__
441
    FileManager   fileManager;
442
#endif
443 444 445 446 447

    /// ATTITUDE
    bool attitudeKnown;             ///< True if attitude was received, false else
    bool attitudeStamped;           ///< Should arriving data be timestamped with the last attitude? This helps with broken system time clocks on the MAV
    quint64 lastAttitude;           ///< Timestamp of last attitude measurement
448 449 450 451
    double roll;
    double pitch;
    double yaw;

452 453
    // dongfang: This looks like a candidate for being moved off to a separate class.
    /// IMAGING
454 455
    int imageSize;              ///< Image size being transmitted (bytes)
    int imagePackets;           ///< Number of data packets being sent for this image
nopeppermint's avatar
nopeppermint committed
456
    int imagePacketsArrived;    ///< Number of data packets received
457 458 459 460 461 462 463 464
    int imagePayload;           ///< Payload size per transmitted packet (bytes). Standard is 254, and decreases when image resolution increases.
    int imageQuality;           ///< Quality of the transmitted image (percentage)
    int imageType;              ///< Type of the transmitted image (BMP, PNG, JPEG, RAW 8 bit, RAW 32 bit)
    int imageWidth;             ///< Width of the image stream
    int imageHeight;            ///< Width of the image stream
    QByteArray imageRecBuffer;  ///< Buffer for the incoming bytestream
    QImage image;               ///< Image data of last completely transmitted image
    quint64 imageStart;
465
    bool blockHomePositionChanges;   ///< Block changes to the home position
466
    bool receivedMode;          ///< True if mode was retrieved from current conenction to UAS
467

468 469 470 471 472 473 474 475 476 477 478 479 480 481 482
    /// SIMULATION NOISE
    float xacc_var;             ///< variance of x acclerometer noise for HIL sim (mg)
    float yacc_var;             ///< variance of y acclerometer noise for HIL sim (mg)
    float zacc_var;             ///< variance of z acclerometer noise for HIL sim (mg)
    float rollspeed_var;        ///< variance of x gyroscope noise for HIL sim (rad/s)
    float pitchspeed_var;       ///< variance of y gyroscope noise for HIL sim (rad/s)
    float yawspeed_var;         ///< variance of z gyroscope noise for HIL sim (rad/s)
    float xmag_var;             ///< variance of x magnatometer noise for HIL sim (???)
    float ymag_var;             ///< variance of y magnatometer noise for HIL sim (???)
    float zmag_var;             ///< variance of z magnatometer noise for HIL sim (???)
    float abs_pressure_var;     ///< variance of absolute pressure noise for HIL sim (hPa)
    float diff_pressure_var;    ///< variance of differential pressure noise for HIL sim (hPa)
    float pressure_alt_var;     ///< variance of altitude pressure noise for HIL sim (hPa)
    float temperature_var;      ///< variance of temperature noise for HIL sim (C)

483
    /// SIMULATION
dogmaphobic's avatar
dogmaphobic committed
484
#ifndef __mobile__
485
    QGCHilLink* simulation;         ///< Hardware in the loop simulation link
dogmaphobic's avatar
dogmaphobic committed
486
#endif
487 488 489 490 491 492 493

public:
    /** @brief Get the current charge level */
    float getChargeLevel();
    /** @brief Get the human-readable status message for this code */
    void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription);

494 495 496
#ifndef __mobile__
    virtual FileManager* getFileManager() { return &fileManager; }
#endif
497

498
    /** @brief Get the HIL simulation */
dogmaphobic's avatar
dogmaphobic committed
499
#ifndef __mobile__
500 501 502
    QGCHilLink* getHILSimulation() const {
        return simulation;
    }
dogmaphobic's avatar
dogmaphobic committed
503
#endif
504

505 506 507 508 509 510
    QImage getImage();
    void requestImage();

public slots:
    /** @brief Executes a command with 7 params */
    void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, float param5, float param6, float param7, int component);
Don Gagne's avatar
Don Gagne committed
511

512 513 514
    /** @brief Order the robot to pair its receiver **/
    void pairRX(int rxType, int rxSubType);

515
    /** @brief Enable / disable HIL */
dogmaphobic's avatar
dogmaphobic committed
516
#ifndef __mobile__
517
    void enableHilFlightGear(bool enable, QString options, bool sensorHil, QObject * configuration);
518
    void enableHilJSBSim(bool enable, QString options);
519 520 521
    void enableHilXPlane(bool enable);

    /** @brief Send the full HIL state to the MAV */
522 523
    void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollRotationRate,
                        float pitchRotationRate, float yawRotationRate, double lat, double lon, double alt,
524 525 526 527 528
                        float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc);

    void sendHilGroundTruth(quint64 time_us, float roll, float pitch, float yaw, float rollRotationRate,
                        float pitchRotationRate, float yawRotationRate, double lat, double lon, double alt,
                        float vx, float vy, float vz, float ind_airspeed, float true_airspeed, float xacc, float yacc, float zacc);
529

Lorenz Meier's avatar
Lorenz Meier committed
530
    /** @brief RAW sensors for sensor HIL */
531 532
    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, quint32 fields_changed);
Lorenz Meier's avatar
Lorenz Meier committed
533

534 535 536 537
    /** @brief Send Optical Flow sensor message for HIL, (arguments and units accoding to mavlink documentation*/
    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);

538 539
    float addZeroMeanNoise(float truth_meas, float noise_var);

Lorenz Meier's avatar
Lorenz Meier committed
540 541 542 543 544 545 546 547 548 549 550 551
    /**
     * @param time_us
     * @param lat
     * @param lon
     * @param alt
     * @param fix_type
     * @param eph
     * @param epv
     * @param vel
     * @param cog course over ground, in radians, -pi..pi
     * @param satellites
     */
552
    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);
Lorenz Meier's avatar
Lorenz Meier committed
553 554


555 556 557 558 559
    /** @brief Places the UAV in Hardware-in-the-Loop simulation status **/
    void startHil();

    /** @brief Stops the UAV's Hardware-in-the-Loop simulation status **/
    void stopHil();
dogmaphobic's avatar
dogmaphobic committed
560
#endif
561 562 563 564 565

    void startLowBattAlarm();
    void stopLowBattAlarm();

    /** @brief Set the values for the manual control of the vehicle */
566
    void setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode);
567 568

    /** @brief Set the values for the 6dof manual control of the vehicle */
dogmaphobic's avatar
dogmaphobic committed
569
#ifndef __mobile__
570
    void setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw);
dogmaphobic's avatar
dogmaphobic committed
571
#endif
572 573

    /** @brief Receive a message from one of the communication links. */
574
    virtual void receiveMessage(mavlink_message_t message);
575

576 577
    void startCalibration(StartCalibrationType calType);
    void stopCalibration(void);
578

579 580 581
    void startBusConfig(StartBusConfigType calType);
    void stopBusConfig(void);

582
    /** @brief Send command to map a RC channel to a parameter */
583
    void sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax);
584 585 586

    /** @brief Send command to disable all bindings/maps between RC and parameters */
    void unsetRCToParameterMap();
587 588 589 590 591 592
signals:
    void loadChanged(UASInterface* uas, double load);
    void imageStarted(quint64 timestamp);
    /** @brief A new camera image has arrived */
    void imageReady(UASInterface* uas);
    /** @brief HIL controls have changed */
593
    void hilControlsChanged(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode);
594

595 596 597 598 599
    void localXChanged(double val,QString name);
    void localYChanged(double val,QString name);
    void localZChanged(double val,QString name);
    void longitudeChanged(double val,QString name);
    void latitudeChanged(double val,QString name);
600
    void altitudeAMSLChanged(double val,QString name);
601
    void altitudeAMSLFTChanged(double val,QString name);
602
    void altitudeRelativeChanged(double val,QString name);
603 604 605 606 607

    void satRawHDOPChanged  (double value);
    void satRawVDOPChanged  (double value);
    void satRawCOGChanged   (double value);

608 609 610 611
    void rollChanged(double val,QString name);
    void pitchChanged(double val,QString name);
    void yawChanged(double val,QString name);
    void satelliteCountChanged(double val,QString name);
612
    void distToWaypointChanged(double val,QString name);
613
    void groundSpeedChanged(double val, QString name);
614
    void airSpeedChanged(double val, QString name);
615
    void bearingToWaypointChanged(double val,QString name);
616 617 618 619 620 621 622
protected:
    /** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
    quint64 getUnixTime(quint64 time=0);
    /** @brief Get the UNIX timestamp in milliseconds, enter milliseconds */
    quint64 getUnixTimeFromMs(quint64 time);
    /** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
    quint64 getUnixReferenceTime(quint64 time);
623

624 625
    virtual void processParamValueMsg(mavlink_message_t& msg, const QString& paramName,const mavlink_param_value_t& rawValue, mavlink_param_union_t& paramValue);

626 627 628 629 630 631 632
    int componentID[256];
    bool componentMulti[256];
    bool connectionLost; ///< Flag indicates a timed out connection
    quint64 connectionLossTime; ///< Time the connection was interrupted
    quint64 lastVoltageWarning; ///< Time at which the last voltage warning occured
    quint64 lastNonNullTime;    ///< The last timestamp from the MAV that was not null
    unsigned int onboardTimeOffsetInvalidCount;     ///< Count when the offboard time offset estimation seemed wrong
Don Gagne's avatar
Don Gagne committed
633
    bool hilEnabled;
634
    bool sensorHil;             ///< True if sensor HIL is enabled
635
    quint64 lastSendTimeGPS;     ///< Last HIL GPS message sent
636 637
    quint64 lastSendTimeSensors; ///< Last HIL Sensors message sent
    quint64 lastSendTimeOpticalFlow; ///< Last HIL Optical Flow message sent
638

639 640
private:
    void _say(const QString& text, int severity = 6);
641

642
private:
643 644
    Vehicle*                _vehicle;
    FirmwarePluginManager*  _firmwarePluginManager;
645 646 647 648
};


#endif // _UAS_H_