UAS.h 24.3 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

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

/**
 * @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 "MG.h"
37
#include <MAVLinkProtocol.h>
pixhawk's avatar
pixhawk committed
38
#include "QGCMAVLink.h"
lm's avatar
lm committed
39
#include "QGCFlightGearLink.h"
pixhawk's avatar
pixhawk committed
40 41 42 43 44 45 46 47 48

/**
 * @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.
 */
49 50
class UAS : public UASInterface
{
pixhawk's avatar
pixhawk committed
51 52
    Q_OBJECT
public:
53
    UAS(MAVLinkProtocol* protocol, int id = 0);
pixhawk's avatar
pixhawk committed
54 55
    ~UAS();

56
    enum BatteryType {
pixhawk's avatar
pixhawk committed
57 58 59 60 61 62
        NICD = 0,
        NIMH = 1,
        LIION = 2,
        LIPOLY = 3,
        LIFE = 4,
        AGZN = 5
63
    }; ///< The type of battery used
pixhawk's avatar
pixhawk committed
64 65 66 67 68 69 70

    static const int lipoFull = 4.2f;  ///< 100% charged voltage
    static const int lipoEmpty = 3.5f; ///< Discharged voltage

    /* MANAGEMENT */

    /** @brief The name of the robot */
71
    QString getUASName(void) const;
72 73 74 75
    /** @brief Get short state */
    const QString& getShortState() const;
    /** @brief Get short mode */
    const QString& getShortMode() const;
76 77
    /** @brief Translate from mode id to text */
    static QString getShortModeTextFor(int id);
78 79
    /** @brief Translate from mode id to audio text */
    static QString getAudioModeTextFor(int id);
pixhawk's avatar
pixhawk committed
80
    /** @brief Get the unique system id */
81
    int getUASID() const;
82
    /** @brief Get the airframe */
83 84 85
    int getAirframe() const {
        return airframe;
    }
LM's avatar
LM committed
86 87 88
    /** @brief Get the components */
    QMap<int, QString> getComponents();

pixhawk's avatar
pixhawk committed
89
    /** @brief The time interval the robot is switched on */
90
    quint64 getUptime() const;
pixhawk's avatar
pixhawk committed
91
    /** @brief Get the status flag for the communication */
92
    int getCommunicationStatus() const;
pixhawk's avatar
pixhawk committed
93
    /** @brief Add one measurement and get low-passed voltage */
94
    float filterVoltage(float value) const;
pixhawk's avatar
pixhawk committed
95 96 97
    /** @brief Get the links associated with this robot */
    QList<LinkInterface*>* getLinks();

LM's avatar
LM committed
98 99
    double getLocalX() const
    {
100 101
        return localX;
    }
LM's avatar
LM committed
102 103
    double getLocalY() const
    {
104 105
        return localY;
    }
LM's avatar
LM committed
106 107
    double getLocalZ() const
    {
108 109 110 111 112 113 114 115 116 117 118
        return localZ;
    }
    double getLatitude() const {
        return latitude;
    }
    double getLongitude() const {
        return longitude;
    }
    double getAltitude() const {
        return altitude;
    }
119 120 121 122 123 124 125 126
    virtual bool localPositionKnown() const
    {
        return isLocalPositionKnown;
    }
    virtual bool globalPositionKnown() const
    {
        return isGlobalPositionKnown;
    }
127 128 129 130 131 132 133 134 135 136

    double getRoll() const {
        return roll;
    }
    double getPitch() const {
        return pitch;
    }
    double getYaw() const {
        return yaw;
    }
137
    bool getSelected() const;
lm's avatar
lm committed
138

139
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
140 141 142
    px::GLOverlay getOverlay() {
        QMutexLocker locker(&overlayMutex);
        return overlay;
143
    }
144

145 146 147 148
    px::GLOverlay getOverlay(qreal& receivedTimestamp) {
        receivedTimestamp = receivedOverlayTimestamp;
        QMutexLocker locker(&overlayMutex);
        return overlay;
149 150
    }

151 152
    px::ObstacleList getObstacleList() {
        QMutexLocker locker(&obstacleListMutex);
153 154
        return obstacleList;
    }
155

156
    px::ObstacleList getObstacleList(qreal& receivedTimestamp) {
157
        receivedTimestamp = receivedObstacleListTimestamp;
158
        QMutexLocker locker(&obstacleListMutex);
159 160 161
        return obstacleList;
    }

162 163
    px::Path getPath() {
        QMutexLocker locker(&pathMutex);
164 165
        return path;
    }
166

167
    px::Path getPath(qreal& receivedTimestamp) {
168
        receivedTimestamp = receivedPathTimestamp;
169
        QMutexLocker locker(&pathMutex);
170 171
        return path;
    }
172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193

    px::PointCloudXYZRGB getPointCloud() {
        QMutexLocker locker(&pointCloudMutex);
        return pointCloud;
    }

    px::PointCloudXYZRGB getPointCloud(qreal& receivedTimestamp) {
        receivedTimestamp = receivedPointCloudTimestamp;
        QMutexLocker locker(&pointCloudMutex);
        return pointCloud;
    }

    px::RGBDImage getRGBDImage() {
        QMutexLocker locker(&rgbdImageMutex);
        return rgbdImage;
    }

    px::RGBDImage getRGBDImage(qreal& receivedTimestamp) {
        receivedTimestamp = receivedRGBDImageTimestamp;
        QMutexLocker locker(&rgbdImageMutex);
        return rgbdImage;
    }
194 195
#endif

196
    friend class UASWaypointManager;
197

INIDETAM's avatar
INIDETAM committed
198
protected: //COMMENTS FOR TEST UNIT
199
    int uasId;                    ///< Unique system ID
200
    unsigned char type;           ///< UAS type (from type enum)
pixhawk's avatar
pixhawk committed
201 202 203
    quint64 startTime;            ///< The time the UAS was switched on
    CommStatus commStatus;        ///< Communication status
    QString name;                 ///< Human-friendly name of the vehicle, e.g. bravo
204
    int autopilot;                ///< Type of the Autopilot: -1: None, 0: Generic, 1: PIXHAWK, 2: SLUGS, 3: Ardupilot (up to 15 types), defined in MAV_AUTOPILOT_TYPE ENUM
pixhawk's avatar
pixhawk committed
205
    QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
206
    QList<int> unknownPackets;    ///< Packet IDs which are unknown and have been received
207
    MAVLinkProtocol* mavlink;     ///< Reference to the MAVLink instance
pixhawk's avatar
pixhawk committed
208 209
    BatteryType batteryType;      ///< The battery type
    int cells;                    ///< Number of cells
pixhawk's avatar
pixhawk committed
210

211 212
    UASWaypointManager waypointManager;

pixhawk's avatar
pixhawk committed
213 214 215 216 217
    QList<double> actuatorValues;
    QList<QString> actuatorNames;

    QList<double> motorValues;
    QList<QString> motorNames;
LM's avatar
LM committed
218
    QMap<int, QString> components;  ///< IDs and names of all detected onboard components
pixhawk's avatar
pixhawk committed
219

pixhawk's avatar
pixhawk committed
220 221
    double thrustSum;           ///< Sum of forward/up thrust of all thrust actuators, in Newtons
    double thrustMax;           ///< Maximum forward/up thrust of this vehicle, in Newtons
pixhawk's avatar
pixhawk committed
222 223

    // Battery stats
224 225 226
    float fullVoltage;          ///< Voltage of the fully charged battery (100%)
    float emptyVoltage;         ///< Voltage of the empty battery (0%)
    float startVoltage;         ///< Voltage at system start
227 228 229
    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
230
    float warnVoltage;          ///< Voltage where QGC will start to warn about low battery
231
    float warnLevelPercent;     ///< Warning level, in percent
pixhawk's avatar
pixhawk committed
232 233
    double currentVoltage;      ///< Voltage currently measured
    float lpVoltage;            ///< Low-pass filtered voltage
234 235
    bool batteryRemainingEstimateEnabled; ///< If the estimate is enabled, QGC will try to estimate the remaining battery life
    float chargeLevel;          ///< Charge level of battery, in percent
pixhawk's avatar
pixhawk committed
236
    int timeRemaining;          ///< Remaining time calculated based on previous and current
LM's avatar
LM committed
237 238
    uint8_t mode;              ///< The current mode of the MAV
    uint32_t custom_mode;       ///< The current mode of the MAV
pixhawk's avatar
pixhawk committed
239
    int status;                 ///< The current status of the MAV
240
    uint32_t navMode;                ///< The current navigation mode of the MAV
pixhawk's avatar
pixhawk committed
241 242
    quint64 onboardTimeOffset;

pixhawk's avatar
pixhawk committed
243 244 245 246 247 248 249 250 251
    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)
lm's avatar
lm committed
252 253
    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
lm's avatar
lm committed
254
    bool lowBattAlarm;          ///< Switch if battery is low
255
    bool positionLock;          ///< Status if position information is available or not
lm's avatar
lm committed
256 257 258
    double localX;
    double localY;
    double localZ;
259 260 261
    double latitude;
    double longitude;
    double altitude;
262 263 264
    double speedX;              ///< True speed in X axis
    double speedY;              ///< True speed in Y axis
    double speedZ;              ///< True speed in Z axis
lm's avatar
lm committed
265 266 267
    double roll;
    double pitch;
    double yaw;
268
    quint64 lastHeartbeat;      ///< Time of the last heartbeat message
269
    QTimer* statusTimeout;      ///< Timer for various status timeouts
270 271 272 273 274

    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.
LM's avatar
LM committed
275 276
    int imageQuality;           ///< Quality of the transmitted image (percentage)
    int imageType;              ///< Type of the transmitted image (BMP, PNG, JPEG, RAW 8 bit, RAW 32 bit)
LM's avatar
LM committed
277 278
    int imageWidth;             ///< Width of the image stream
    int imageHeight;            ///< Width of the image stream
279 280 281 282
    QByteArray imageRecBuffer;  ///< Buffer for the incoming bytestream
    QImage image;               ///< Image data of last completely transmitted image
    quint64 imageStart;

283
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
284 285 286
    px::GLOverlay overlay;
    QMutex overlayMutex;
    qreal receivedOverlayTimestamp;
287

288
    px::ObstacleList obstacleList;
289
    QMutex obstacleListMutex;
290 291
    qreal receivedObstacleListTimestamp;

292
    px::Path path;
293
    QMutex pathMutex;
294
    qreal receivedPathTimestamp;
295 296 297 298 299 300 301 302

    px::PointCloudXYZRGB pointCloud;
    QMutex pointCloudMutex;
    qreal receivedPointCloudTimestamp;

    px::RGBDImage rgbdImage;
    QMutex rgbdImageMutex;
    qreal receivedRGBDImageTimestamp;
303 304
#endif

305
    QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
lm's avatar
lm committed
306 307 308
    bool paramsOnceRequested;       ///< If the parameter list has been read at least once
    int airframe;                   ///< The airframe type
    bool attitudeKnown;             ///< True if attitude was received, false else
309
    QGCUASParamManager* paramManager; ///< Parameter manager class
lm's avatar
lm committed
310 311 312 313 314 315 316
    QString shortStateText;         ///< Short textual state description
    QString shortModeText;          ///< Short textual mode description
    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
    QGCFlightGearLink* simulation;  ///< Hardware in the loop simulation link
    bool isLocalPositionKnown;      ///< If the local position has been received for this MAV
    bool isGlobalPositionKnown;     ///< If the global position has been received for this MAV
317
    bool systemIsArmed;             ///< If the system is armed
lm's avatar
lm committed
318

319
public:
pixhawk's avatar
pixhawk committed
320 321 322 323 324
    /** @brief Set the current battery type */
    void setBattery(BatteryType type, int cells);
    /** @brief Estimate how much flight time is remaining */
    int calculateTimeRemaining();
    /** @brief Get the current charge level */
325
    float getChargeLevel();
pixhawk's avatar
pixhawk committed
326 327
    /** @brief Get the human-readable status message for this code */
    void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription);
328 329
    /** @brief Get the human-readable navigation mode translation for this mode */
    QString getNavModeText(int mode);
pixhawk's avatar
pixhawk committed
330 331
    /** @brief Check if vehicle is in autonomous mode */
    bool isAuto();
332 333
    /** @brief Check if vehicle is armed */
    bool isArmed() const { return systemIsArmed; }
pixhawk's avatar
pixhawk committed
334

335 336 337
    UASWaypointManager* getWaypointManager() {
        return &waypointManager;
    }
338
    /** @brief Get reference to the param manager **/
339 340 341
    QGCUASParamManager* getParamManager() const {
        return paramManager;
    }
342 343
    // TODO Will be removed
    /** @brief Set reference to the param manager **/
344 345 346
    void setParamManager(QGCUASParamManager* manager) {
        paramManager = manager;
    }
347
    int getSystemType();
lm's avatar
lm committed
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 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408
    QString getSystemTypeName()
    {
        switch(type)
        {
        case MAV_TYPE_GENERIC:
            return "GENERIC";
            break;
        case MAV_TYPE_FIXED_WING:
            return "FIXED_WING";
            break;
        case MAV_TYPE_QUADROTOR:
            return "QUADROTOR";
            break;
        case MAV_TYPE_COAXIAL:
            return "COAXIAL";
            break;
        case MAV_TYPE_HELICOPTER:
            return "HELICOPTER";
            break;
        case MAV_TYPE_ANTENNA_TRACKER:
            return "ANTENNA_TRACKER";
            break;
        case MAV_TYPE_GCS:
            return "GCS";
            break;
        case MAV_TYPE_AIRSHIP:
            return "AIRSHIP";
            break;
        case MAV_TYPE_FREE_BALLOON:
            return "FREE_BALLOON";
            break;
        case MAV_TYPE_ROCKET:
            return "ROCKET";
            break;
        case MAV_TYPE_GROUND_ROVER:
            return "GROUND_ROVER";
            break;
        case MAV_TYPE_SURFACE_BOAT:
            return "BOAT";
            break;
        case MAV_TYPE_SUBMARINE:
            return "SUBMARINE";
            break;
        case MAV_TYPE_HEXAROTOR:
            return "HEXAROTOR";
            break;
        case MAV_TYPE_OCTOROTOR:
            return "OCTOROTOR";
            break;
        case MAV_TYPE_TRICOPTER:
            return "TRICOPTER";
            break;
        case MAV_TYPE_FLAPPING_WING:
            return "FLAPPING_WING";
            break;
        default:
            return "";
            break;
        }
    }

409
    QImage getImage();
410
    void requestImage();
411 412 413
    int getAutopilotType() {
        return autopilot;
    }
lm's avatar
lm committed
414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432
    QString getAutopilotTypeName()
    {
        switch (autopilot)
        {
        case MAV_AUTOPILOT_GENERIC:
            return "GENERIC";
            break;
        case MAV_AUTOPILOT_PIXHAWK:
            return "PIXHAWK";
            break;
        case MAV_AUTOPILOT_SLUGS:
            return "SLUGS";
            break;
        case MAV_AUTOPILOT_ARDUPILOTMEGA:
            return "ARDUPILOTMEGA";
            break;
        case MAV_AUTOPILOT_OPENPILOT:
            return "OPENPILOT";
            break;
lm's avatar
lm committed
433 434
        case MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY:
            return "GENERIC_WAYPOINTS_ONLY";
lm's avatar
lm committed
435
            break;
lm's avatar
lm committed
436
        case MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY:
lm's avatar
lm committed
437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458
            return "GENERIC_MISSION_NAVIGATION_ONLY";
            break;
        case MAV_AUTOPILOT_GENERIC_MISSION_FULL:
            return "GENERIC_MISSION_FULL";
            break;
        case MAV_AUTOPILOT_INVALID:
            return "NO AP";
            break;
        case MAV_AUTOPILOT_PPZ:
            return "PPZ";
            break;
        case MAV_AUTOPILOT_UDB:
            return "UDB";
            break;
        case MAV_AUTOPILOT_FP:
            return "FP";
            break;
        default:
            return "";
            break;
        }
    }
459

pixhawk's avatar
pixhawk committed
460
public slots:
461
    /** @brief Set the autopilot type */
lm's avatar
lm committed
462 463
    void setAutopilotType(int apType)
    {
464 465 466
        autopilot = apType;
        emit systemSpecsChanged(uasId);
    }
467
    /** @brief Set the type of airframe */
468
    void setSystemType(int systemType);
469
    /** @brief Set the specific airframe type */
lm's avatar
lm committed
470 471
    void setAirframe(int airframe)
    {
472 473 474
        this->airframe = airframe;
        emit systemSpecsChanged(uasId);
    }
475 476
    /** @brief Set a new name **/
    void setUASName(const QString& name);
lm's avatar
lm committed
477 478
    /** @brief Executes a command **/
    void executeCommand(MAV_CMD command);
479 480
    /** @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);
481 482 483 484
    /** @brief Set the current battery type and voltages */
    void setBatterySpecs(const QString& specs);
    /** @brief Get the current battery type and specs */
    QString getBatterySpecs();
485

pixhawk's avatar
pixhawk committed
486 487
    /** @brief Launches the system **/
    void launch();
lm's avatar
lm committed
488
    /** @brief Write this waypoint to the list of waypoints */
489
    //void setWaypoint(Waypoint* wp); FIXME tbd
lm's avatar
lm committed
490
    /** @brief Set currently active waypoint */
491
    //void setWaypointActive(int id); FIXME tbd
pixhawk's avatar
pixhawk committed
492 493 494 495
    /** @brief Order the robot to return home / to land on the runway **/
    void home();
    void halt();
    void go();
lm's avatar
lm committed
496 497 498 499 500 501 502 503 504 505

    /** @brief Enable / disable HIL */
    void enableHil(bool enable);

    /** @brief Send the full HIL state to the MAV */

    void sendHilState(	uint64_t time_us, float roll, float pitch, float yaw, float rollspeed,
                        float pitchspeed, float yawspeed, int32_t lat, int32_t lon, int32_t alt,
                        int16_t vx, int16_t vy, int16_t vz, int16_t xacc, int16_t yacc, int16_t zacc);

506 507 508 509 510 511 512
    /** @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();


pixhawk's avatar
pixhawk committed
513 514 515 516 517 518 519 520 521
    /** @brief Stops the robot system. If it is an MAV, the robot starts the emergency landing procedure **/
    void emergencySTOP();

    /** @brief Kills the robot. All systems are immediately shut down (e.g. the main power line is cut). This might lead to a crash **/
    bool emergencyKILL();

    /** @brief Shut the system cleanly down. Will shut down any onboard computers **/
    void shutdown();

522 523 524
    /** @brief Set the target position for the robot to navigate to. */
    void setTargetPosition(float x, float y, float z, float yaw);

lm's avatar
lm committed
525 526 527
    void startLowBattAlarm();
    void stopLowBattAlarm();

528 529
    /** @brief Arm system */
    void armSystem();
pixhawk's avatar
pixhawk committed
530
    /** @brief Disable the motors */
531
    void disarmSystem();
pixhawk's avatar
pixhawk committed
532 533 534 535 536 537

    /** @brief Set the values for the manual control of the vehicle */
    void setManualControlCommands(double roll, double pitch, double yaw, double thrust);
    /** @brief Receive a button pressed event from an input device, e.g. joystick */
    void receiveButton(int buttonIndex);

pixhawk's avatar
pixhawk committed
538
    /** @brief Add a link associated with this robot */
pixhawk's avatar
pixhawk committed
539
    void addLink(LinkInterface* link);
540 541
    /** @brief Remove a link associated with this robot */
    void removeLink(QObject* object);
pixhawk's avatar
pixhawk committed
542 543

    /** @brief Receive a message from one of the communication links. */
544
    virtual void receiveMessage(LinkInterface* link, mavlink_message_t message);
pixhawk's avatar
pixhawk committed
545

546 547 548 549 550
#ifdef QGC_PROTOBUF_ENABLED
    /** @brief Receive a message from one of the communication links. */
    virtual void receiveExtendedMessage(LinkInterface* link, std::tr1::shared_ptr<google::protobuf::Message> message);
#endif

pixhawk's avatar
pixhawk committed
551 552 553 554 555
    /** @brief Send a message over this link (to this or to all UAS on this link) */
    void sendMessage(LinkInterface* link, mavlink_message_t message);
    /** @brief Send a message over all links this UAS can be reached with (!= all links) */
    void sendMessage(mavlink_message_t message);

556 557 558
    /** @brief Temporary Hack for sending packets to patch Antenna. Send a message over all serial links except for this UAS's */
    void forwardMessage(mavlink_message_t message);

pixhawk's avatar
pixhawk committed
559 560 561 562
    /** @brief Set this UAS as the system currently in focus, e.g. in the main display widgets */
    void setSelected();

    /** @brief Set current mode of operation, e.g. auto or manual */
pixhawk's avatar
pixhawk committed
563
    void setMode(int mode);
pixhawk's avatar
pixhawk committed
564

565 566 567
    /** @brief Request all parameters */
    void requestParameters();

568
    /** @brief Request a single parameter by name */
569
    void requestParameter(int component, const QString& parameter);
570
    /** @brief Request a single parameter by index */
571
    void requestParameter(int component, int id);
572

573
    /** @brief Set a system parameter */
574
    void setParameter(const int component, const QString& id, const QVariant& value);
575 576

    /** @brief Write parameters to permanent storage */
577 578 579
    void writeParametersToStorage();
    /** @brief Read parameters from permanent storage */
    void readParametersFromStorage();
580

581 582 583 584 585 586
    /** @brief Get the names of all parameters */
    QList<QString> getParameterNames(int component);

    /** @brief Get the ids of all components */
    QList<int> getComponentIds();

587 588 589 590 591
    void enableAllDataTransmission(int rate);
    void enableRawSensorDataTransmission(int rate);
    void enableExtendedSystemStatusTransmission(int rate);
    void enableRCChannelDataTransmission(int rate);
    void enableRawControllerDataTransmission(int rate);
lm's avatar
lm committed
592
    //void enableRawSensorFusionTransmission(int rate);
593 594 595 596
    void enablePositionTransmission(int rate);
    void enableExtra1Transmission(int rate);
    void enableExtra2Transmission(int rate);
    void enableExtra3Transmission(int rate);
lm's avatar
lm committed
597

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

601 602
    /** @brief Set world frame origin at current GPS position */
    void setLocalOriginAtCurrentGPSPosition();
603 604
    /** @brief Set world frame origin / home position at this GPS position */
    void setHomePosition(double lat, double lon, double alt);
pixhawk's avatar
pixhawk committed
605 606
    /** @brief Set local position setpoint */
    void setLocalPositionSetpoint(float x, float y, float z, float yaw);
pixhawk's avatar
pixhawk committed
607 608 609 610 611 612 613
    /** @brief Add an offset in body frame to the setpoint */
    void setLocalPositionOffset(float x, float y, float z, float yaw);

    void startRadioControlCalibration();
    void startMagnetometerCalibration();
    void startGyroscopeCalibration();
    void startPressureCalibration();
pixhawk's avatar
pixhawk committed
614

lm's avatar
lm committed
615 616 617
    void startDataRecording();
    void stopDataRecording();

pixhawk's avatar
pixhawk committed
618 619 620
signals:

    /** @brief The main/battery voltage has changed/was updated */
621
    //void voltageChanged(int uasId, double voltage); // Defined in UASInterface already
pixhawk's avatar
pixhawk committed
622
    /** @brief An actuator value has changed */
623
    //void actuatorChanged(UASInterface*, int actId, double value); // Defined in UASInterface already
pixhawk's avatar
pixhawk committed
624 625 626 627 628 629
    /** @brief An actuator value has changed */
    void actuatorChanged(UASInterface* uas, QString actuatorName, double min, double max, double value);
    void motorChanged(UASInterface* uas, QString motorName, double min, double max, double value);
    /** @brief The system load (MCU/CPU usage) changed */
    void loadChanged(UASInterface* uas, double load);
    /** @brief Propagate a heartbeat received from the system */
630
    //void heartbeat(UASInterface* uas); // Defined in UASInterface already
631
    void imageStarted(quint64 timestamp);
632 633
    /** @brief A new camera image has arrived */
    void imageReady(UASInterface* uas);
lm's avatar
lm committed
634 635
    /** @brief HIL controls have changed */
    void hilControlsChanged(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode);
636

637
protected:
638
    /** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
639
    quint64 getUnixTime(quint64 time=0);
640 641
    /** @brief Get the UNIX timestamp in milliseconds, enter milliseconds */
    quint64 getUnixTimeFromMs(quint64 time);
LM's avatar
LM committed
642 643
    /** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
    quint64 getUnixReferenceTime(quint64 time);
644 645
    int componentID[256];
    bool componentMulti[256];
646 647

protected slots:
648 649 650 651
    /** @brief Write settings to disk */
    void writeSettings();
    /** @brief Read settings from disk */
    void readSettings();
652

653 654 655
//    // MESSAGE RECEPTION
//    /** @brief Receive a named value message */
//    void receiveMessageNamedValue(const mavlink_message_t& message);
656 657

private:
658
//    unsigned int mode;          ///< The current mode of the MAV
pixhawk's avatar
pixhawk committed
659 660 661 662
};


#endif // _UAS_H_