UAS.h 25.8 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 100
    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   altitudeWGS84           READ getAltitudeWGS84       WRITE setAltitudeWGS84      NOTIFY altitudeWGS84Changed)
    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)
101

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

105 106 107 108 109 110 111 112 113 114
    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;
    }
115

116 117 118 119 120 121 122 123 124 125 126
    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;
    }
127 128 129 130 131

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

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

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

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

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

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

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

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

186
    void setAltitudeAMSL(double val)
187
    {
188 189
        altitudeAMSL = val;
        emit altitudeAMSLChanged(val, "altitudeAMSL");
190 191 192 193
        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());
194 195
    }

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

201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218
    double getAltitudeAMSLFT() const
    {
        return altitudeAMSLFT;
    }

    void setAltitudeWGS84(double val)
    {
        altitudeWGS84 = val;
        emit altitudeWGS84Changed(val, "altitudeWGS84");
        emit valueChanged(this->uasId,"altitudeWGS84","m",QVariant(val),getUnixTime());
    }

    double getAltitudeWGS84() const
    {
        return altitudeWGS84;
    }


219 220 221 222 223 224 225 226 227 228
    void setAltitudeRelative(double val)
    {
        altitudeRelative = val;
        emit altitudeRelativeChanged(val, "altitudeRelative");
        emit valueChanged(this->uasId,"altitudeRelative","m",QVariant(val),getUnixTime());
    }

    double getAltitudeRelative() const
    {
        return altitudeRelative;
229
    }
230

231 232 233 234 235 236 237 238 239 240 241 242 243 244 245
    double getSatRawHDOP() const
    {
        return satRawHDOP;
    }

    double getSatRawVDOP() const
    {
        return satRawVDOP;
    }

    double getSatRawCOG() const
    {
        return satRawCOG;
    }

246 247 248 249
    void setSatelliteCount(double val)
    {
        satelliteCount = val;
        emit satelliteCountChanged(val,"satelliteCount");
250
        emit valueChanged(this->uasId,"satelliteCount","",QVariant(val),getUnixTime());
251 252 253 254 255 256 257
    }

    double getSatelliteCount() const
    {
        return satelliteCount;
    }

258 259 260 261 262
    virtual bool globalPositionKnown() const
    {
        return isGlobalPositionKnown;
    }

263 264 265 266
    void setDistToWaypoint(double val)
    {
        distToWaypoint = val;
        emit distToWaypointChanged(val,"distToWaypoint");
267
        emit valueChanged(this->uasId,"distToWaypoint","m",QVariant(val),getUnixTime());
268 269 270 271 272 273 274
    }

    double getDistToWaypoint() const
    {
        return distToWaypoint;
    }

275 276 277 278
    void setBearingToWaypoint(double val)
    {
        bearingToWaypoint = val;
        emit bearingToWaypointChanged(val,"bearingToWaypoint");
279
        emit valueChanged(this->uasId,"bearingToWaypoint","deg",QVariant(val),getUnixTime());
280 281 282 283 284 285 286 287
    }

    double getBearingToWaypoint() const
    {
        return bearingToWaypoint;
    }


288 289 290 291 292 293
    void setRoll(double val)
    {
        roll = val;
        emit rollChanged(val,"roll");
    }

294 295 296 297
    double getRoll() const
    {
        return roll;
    }
298 299 300 301 302 303 304

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

305 306 307 308
    double getPitch() const
    {
        return pitch;
    }
309 310 311 312 313 314 315

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

316 317 318 319
    double getYaw() const
    {
        return yaw;
    }
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 360 361 362 363 364 365 366 367 368 369 370 371 372 373
    // 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;
    }

374
#ifndef __mobile__
375
    friend class FileManager;
376
#endif
377 378

protected: //COMMENTS FOR TEST UNIT
379
    /// LINK ID AND STATUS
380
    int uasId;                    ///< Unique system ID
381
    QMap<int, QString> components;///< IDs and names of all detected onboard components
382

383 384
    QList<int> unknownPackets;    ///< Packet IDs which are unknown and have been received
    MAVLinkProtocol* mavlink;     ///< Reference to the MAVLink instance
385 386 387
    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
    quint64 lastHeartbeat;        ///< Time of the last heartbeat message
388
    QTimer statusTimeout;       ///< Timer for various status timeouts
389

390
    /// BASIC UAS TYPE, NAME AND STATE
391
    uint8_t base_mode;                 ///< The current mode of the MAV
392 393
    uint32_t custom_mode;         ///< The current mode of the MAV
    int status;                   ///< The current status of the MAV
394

395 396
    // dongfang: This looks like a candidate for being moved off to a separate class.
    /// BATTERY / ENERGY
397 398 399 400 401 402 403
    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
404
    double currentCurrent;      ///< Battery current currently measured
405 406
    bool batteryRemainingEstimateEnabled; ///< If the estimate is enabled, QGC will try to estimate the remaining battery life
    float chargeLevel;          ///< Charge level of battery, in percent
407 408 409 410 411
    bool lowBattAlarm;          ///< Switch if battery is low


    /// TIMEKEEPING
    quint64 startTime;            ///< The time the UAS was switched on
412 413
    quint64 onboardTimeOffset;

414
    /// MANUAL CONTROL
415 416 417 418 419 420 421 422 423
    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)
424 425

    /// POSITION
426
    bool positionLock;          ///< Status if position information is available or not
427
    bool isGlobalPositionKnown; ///< If the global position has been received for this MAV
428

429 430 431
    double localX;
    double localY;
    double localZ;
432

433 434
    double latitude;            ///< Global latitude as estimated by position estimator
    double longitude;           ///< Global longitude as estimated by position estimator
435
    double altitudeAMSL;        ///< Global altitude as estimated by position estimator, AMSL
436 437
    double altitudeAMSLFT;      ///< Global altitude as estimated by position estimator, AMSL
    double altitudeWGS84;       ///< Global altitude as estimated by position estimator, WGS84
438
    double altitudeRelative;    ///< Altitude above home as estimated by position estimator
439

440 441 442 443
    double satRawHDOP;
    double satRawVDOP;
    double satRawCOG;

444
    double satelliteCount;      ///< Number of satellites visible to raw GPS
445 446 447 448
    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
449 450 451
    double speedX;              ///< True speed in X axis
    double speedY;              ///< True speed in Y axis
    double speedZ;              ///< True speed in Z axis
452 453

    /// WAYPOINT NAVIGATION
454
    double distToWaypoint;       ///< Distance to next waypoint
455 456
    double airSpeed;             ///< Airspeed
    double groundSpeed;          ///< Groundspeed
457
    double bearingToWaypoint;    ///< Bearing to next waypoint
458
#ifndef __mobile__
459
    FileManager   fileManager;
460
#endif
461 462 463 464 465

    /// 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
466 467 468 469
    double roll;
    double pitch;
    double yaw;

470 471
    // dongfang: This looks like a candidate for being moved off to a separate class.
    /// IMAGING
472 473 474 475 476 477 478 479 480 481 482
    int imageSize;              ///< Image size being transmitted (bytes)
    int imagePackets;           ///< Number of data packets being sent for this image
    int imagePacketsArrived;    ///< Number of data packets recieved
    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;
483
    bool blockHomePositionChanges;   ///< Block changes to the home position
484
    bool receivedMode;          ///< True if mode was retrieved from current conenction to UAS
485

486 487 488 489 490 491 492 493 494 495 496 497 498 499 500
    /// 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)

501
    /// SIMULATION
dogmaphobic's avatar
dogmaphobic committed
502
#ifndef __mobile__
503
    QGCHilLink* simulation;         ///< Hardware in the loop simulation link
dogmaphobic's avatar
dogmaphobic committed
504
#endif
505 506 507 508 509 510 511

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

512 513 514
#ifndef __mobile__
    virtual FileManager* getFileManager() { return &fileManager; }
#endif
515

516
    /** @brief Get the HIL simulation */
dogmaphobic's avatar
dogmaphobic committed
517
#ifndef __mobile__
518 519 520
    QGCHilLink* getHILSimulation() const {
        return simulation;
    }
dogmaphobic's avatar
dogmaphobic committed
521
#endif
522

523 524 525 526 527 528
    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
529

530 531 532
    /** @brief Order the robot to pair its receiver **/
    void pairRX(int rxType, int rxSubType);

533
    /** @brief Enable / disable HIL */
dogmaphobic's avatar
dogmaphobic committed
534
#ifndef __mobile__
535
    void enableHilFlightGear(bool enable, QString options, bool sensorHil, QObject * configuration);
536
    void enableHilJSBSim(bool enable, QString options);
537 538 539
    void enableHilXPlane(bool enable);

    /** @brief Send the full HIL state to the MAV */
540 541
    void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollRotationRate,
                        float pitchRotationRate, float yawRotationRate, double lat, double lon, double alt,
542 543 544 545 546
                        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);
547

Lorenz Meier's avatar
Lorenz Meier committed
548
    /** @brief RAW sensors for sensor HIL */
549 550
    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
551

552 553 554 555
    /** @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);

556 557
    float addZeroMeanNoise(float truth_meas, float noise_var);

Lorenz Meier's avatar
Lorenz Meier committed
558 559 560 561 562 563 564 565 566 567 568 569
    /**
     * @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
     */
570
    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
571 572


573 574 575 576 577
    /** @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
578
#endif
579 580 581 582 583

    void startLowBattAlarm();
    void stopLowBattAlarm();

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

    /** @brief Set the values for the 6dof manual control of the vehicle */
dogmaphobic's avatar
dogmaphobic committed
587
#ifndef __mobile__
588
    void setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw);
dogmaphobic's avatar
dogmaphobic committed
589
#endif
590 591

    /** @brief Receive a message from one of the communication links. */
592
    virtual void receiveMessage(mavlink_message_t message);
593 594 595 596

    /** @brief Update the system state */
    void updateState();

597 598
    void startCalibration(StartCalibrationType calType);
    void stopCalibration(void);
599

600 601 602
    void startBusConfig(StartBusConfigType calType);
    void stopBusConfig(void);

603
    /** @brief Send command to map a RC channel to a parameter */
604
    void sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax);
605 606 607

    /** @brief Send command to disable all bindings/maps between RC and parameters */
    void unsetRCToParameterMap();
608 609 610 611 612 613 614 615
signals:
    void loadChanged(UASInterface* uas, double load);
    /** @brief Propagate a heartbeat received from the system */
    //void heartbeat(UASInterface* uas); // Defined in UASInterface already
    void imageStarted(quint64 timestamp);
    /** @brief A new camera image has arrived */
    void imageReady(UASInterface* uas);
    /** @brief HIL controls have changed */
616
    void hilControlsChanged(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode);
617
    /** @brief HIL actuator outputs have changed */
618
    void hilActuatorsChanged(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
619

620 621 622 623 624
    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);
625
    void altitudeAMSLChanged(double val,QString name);
626 627
    void altitudeAMSLFTChanged(double val,QString name);
    void altitudeWGS84Changed(double val,QString name);
628
    void altitudeRelativeChanged(double val,QString name);
629 630 631 632 633

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

634 635 636 637
    void rollChanged(double val,QString name);
    void pitchChanged(double val,QString name);
    void yawChanged(double val,QString name);
    void satelliteCountChanged(double val,QString name);
638
    void distToWaypointChanged(double val,QString name);
639
    void groundSpeedChanged(double val, QString name);
640
    void airSpeedChanged(double val, QString name);
641
    void bearingToWaypointChanged(double val,QString name);
642 643 644 645 646 647 648
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);
649

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

652 653 654 655 656 657 658
    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
659
    bool hilEnabled;
660
    bool sensorHil;             ///< True if sensor HIL is enabled
661
    quint64 lastSendTimeGPS;     ///< Last HIL GPS message sent
662 663
    quint64 lastSendTimeSensors; ///< Last HIL Sensors message sent
    quint64 lastSendTimeOpticalFlow; ///< Last HIL Optical Flow message sent
664

665 666
private:
    void _say(const QString& text, int severity = 6);
667

668
private:
669 670
    Vehicle*                _vehicle;
    FirmwarePluginManager*  _firmwarePluginManager;
671 672 673 674
};


#endif // _UAS_H_