UAS.h 24 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);
pixhawk's avatar
pixhawk committed
78
    /** @brief Get the unique system id */
79
    int getUASID() const;
80
    /** @brief Get the airframe */
81 82 83
    int getAirframe() const {
        return airframe;
    }
LM's avatar
LM committed
84 85 86
    /** @brief Get the components */
    QMap<int, QString> getComponents();

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

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

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

137
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
138 139
    px::PointCloudXYZRGB getPointCloud() {
        QMutexLocker locker(&pointCloudMutex);
140 141
        return pointCloud;
    }
142

143
    px::PointCloudXYZRGB getPointCloud(qreal& receivedTimestamp) {
144
        receivedTimestamp = receivedPointCloudTimestamp;
145
        QMutexLocker locker(&pointCloudMutex);
146 147 148
        return pointCloud;
    }

149 150
    px::RGBDImage getRGBDImage() {
        QMutexLocker locker(&rgbdImageMutex);
151 152
        return rgbdImage;
    }
153

154
    px::RGBDImage getRGBDImage(qreal& receivedTimestamp) {
155
        receivedTimestamp = receivedRGBDImageTimestamp;
156
        QMutexLocker locker(&rgbdImageMutex);
157 158 159
        return rgbdImage;
    }

160 161
    px::ObstacleList getObstacleList() {
        QMutexLocker locker(&obstacleListMutex);
162 163
        return obstacleList;
    }
164

165
    px::ObstacleList getObstacleList(qreal& receivedTimestamp) {
166
        receivedTimestamp = receivedObstacleListTimestamp;
167
        QMutexLocker locker(&obstacleListMutex);
168 169 170
        return obstacleList;
    }

171 172
    px::Path getPath() {
        QMutexLocker locker(&pathMutex);
173 174
        return path;
    }
175

176
    px::Path getPath(qreal& receivedTimestamp) {
177
        receivedTimestamp = receivedPathTimestamp;
178
        QMutexLocker locker(&pathMutex);
179 180
        return path;
    }
181 182
#endif

183
    friend class UASWaypointManager;
184

INIDETAM's avatar
INIDETAM committed
185
protected: //COMMENTS FOR TEST UNIT
186
    int uasId;                    ///< Unique system ID
187
    unsigned char type;           ///< UAS type (from type enum)
pixhawk's avatar
pixhawk committed
188 189 190
    quint64 startTime;            ///< The time the UAS was switched on
    CommStatus commStatus;        ///< Communication status
    QString name;                 ///< Human-friendly name of the vehicle, e.g. bravo
191
    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
192
    QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
193
    QList<int> unknownPackets;    ///< Packet IDs which are unknown and have been received
194
    MAVLinkProtocol* mavlink;     ///< Reference to the MAVLink instance
pixhawk's avatar
pixhawk committed
195 196
    BatteryType batteryType;      ///< The battery type
    int cells;                    ///< Number of cells
pixhawk's avatar
pixhawk committed
197

198 199
    UASWaypointManager waypointManager;

pixhawk's avatar
pixhawk committed
200 201 202 203 204
    QList<double> actuatorValues;
    QList<QString> actuatorNames;

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

pixhawk's avatar
pixhawk committed
207 208
    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
209 210

    // Battery stats
211 212 213
    float fullVoltage;          ///< Voltage of the fully charged battery (100%)
    float emptyVoltage;         ///< Voltage of the empty battery (0%)
    float startVoltage;         ///< Voltage at system start
214
    float warnVoltage;          ///< Voltage where QGC will start to warn about low battery
215
    float warnLevelPercent;     ///< Warning level, in percent
pixhawk's avatar
pixhawk committed
216 217
    double currentVoltage;      ///< Voltage currently measured
    float lpVoltage;            ///< Low-pass filtered voltage
218 219
    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
220
    int timeRemaining;          ///< Remaining time calculated based on previous and current
LM's avatar
LM committed
221
    uint8_t mode;                   ///< The current mode of the MAV
pixhawk's avatar
pixhawk committed
222
    int status;                 ///< The current status of the MAV
223
    uint32_t navMode;                ///< The current navigation mode of the MAV
pixhawk's avatar
pixhawk committed
224 225
    quint64 onboardTimeOffset;

pixhawk's avatar
pixhawk committed
226 227 228 229 230 231 232 233 234
    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
235 236
    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
237
    bool lowBattAlarm;          ///< Switch if battery is low
238
    bool positionLock;          ///< Status if position information is available or not
lm's avatar
lm committed
239 240 241
    double localX;
    double localY;
    double localZ;
242 243 244
    double latitude;
    double longitude;
    double altitude;
245 246 247
    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
248 249 250
    double roll;
    double pitch;
    double yaw;
251
    quint64 lastHeartbeat;      ///< Time of the last heartbeat message
252
    QTimer* statusTimeout;      ///< Timer for various status timeouts
253 254 255 256 257

    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
258 259
    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
260 261
    int imageWidth;             ///< Width of the image stream
    int imageHeight;            ///< Width of the image stream
262 263 264 265
    QByteArray imageRecBuffer;  ///< Buffer for the incoming bytestream
    QImage image;               ///< Image data of last completely transmitted image
    quint64 imageStart;

266
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
267
    px::PointCloudXYZRGB pointCloud;
268
    QMutex pointCloudMutex;
269 270
    qreal receivedPointCloudTimestamp;

271
    px::RGBDImage rgbdImage;
272
    QMutex rgbdImageMutex;
273 274
    qreal receivedRGBDImageTimestamp;

275
    px::ObstacleList obstacleList;
276
    QMutex obstacleListMutex;
277 278
    qreal receivedObstacleListTimestamp;

279
    px::Path path;
280
    QMutex pathMutex;
281
    qreal receivedPathTimestamp;
282 283
#endif

284
    QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
lm's avatar
lm committed
285 286 287
    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
288
    QGCUASParamManager* paramManager; ///< Parameter manager class
lm's avatar
lm committed
289 290 291 292 293 294 295
    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
296
    bool systemIsArmed;             ///< If the system is armed
lm's avatar
lm committed
297

298
public:
pixhawk's avatar
pixhawk committed
299 300 301 302 303
    /** @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 */
304
    float getChargeLevel();
pixhawk's avatar
pixhawk committed
305 306
    /** @brief Get the human-readable status message for this code */
    void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription);
307 308
    /** @brief Get the human-readable navigation mode translation for this mode */
    QString getNavModeText(int mode);
pixhawk's avatar
pixhawk committed
309 310
    /** @brief Check if vehicle is in autonomous mode */
    bool isAuto();
311 312
    /** @brief Check if vehicle is armed */
    bool isArmed() const { return systemIsArmed; }
pixhawk's avatar
pixhawk committed
313

314 315 316
    UASWaypointManager* getWaypointManager() {
        return &waypointManager;
    }
317
    /** @brief Get reference to the param manager **/
318 319 320
    QGCUASParamManager* getParamManager() const {
        return paramManager;
    }
321 322
    // TODO Will be removed
    /** @brief Set reference to the param manager **/
323 324 325
    void setParamManager(QGCUASParamManager* manager) {
        paramManager = manager;
    }
326
    int getSystemType();
lm's avatar
lm committed
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 374 375 376 377 378 379 380 381 382 383 384 385 386 387
    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;
        }
    }

388
    QImage getImage();
389
    void requestImage();
390 391 392
    int getAutopilotType() {
        return autopilot;
    }
lm's avatar
lm committed
393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411
    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
412 413
        case MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY:
            return "GENERIC_WAYPOINTS_ONLY";
lm's avatar
lm committed
414
            break;
lm's avatar
lm committed
415
        case MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY:
lm's avatar
lm committed
416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437
            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;
        }
    }
438

pixhawk's avatar
pixhawk committed
439
public slots:
440
    /** @brief Set the autopilot type */
lm's avatar
lm committed
441 442
    void setAutopilotType(int apType)
    {
443 444 445
        autopilot = apType;
        emit systemSpecsChanged(uasId);
    }
446
    /** @brief Set the type of airframe */
447
    void setSystemType(int systemType);
448
    /** @brief Set the specific airframe type */
lm's avatar
lm committed
449 450
    void setAirframe(int airframe)
    {
451 452 453
        this->airframe = airframe;
        emit systemSpecsChanged(uasId);
    }
454 455
    /** @brief Set a new name **/
    void setUASName(const QString& name);
lm's avatar
lm committed
456 457
    /** @brief Executes a command **/
    void executeCommand(MAV_CMD command);
458 459
    /** @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);
460 461 462 463
    /** @brief Set the current battery type and voltages */
    void setBatterySpecs(const QString& specs);
    /** @brief Get the current battery type and specs */
    QString getBatterySpecs();
464

pixhawk's avatar
pixhawk committed
465 466
    /** @brief Launches the system **/
    void launch();
lm's avatar
lm committed
467
    /** @brief Write this waypoint to the list of waypoints */
468
    //void setWaypoint(Waypoint* wp); FIXME tbd
lm's avatar
lm committed
469
    /** @brief Set currently active waypoint */
470
    //void setWaypointActive(int id); FIXME tbd
pixhawk's avatar
pixhawk committed
471 472 473 474
    /** @brief Order the robot to return home / to land on the runway **/
    void home();
    void halt();
    void go();
lm's avatar
lm committed
475 476 477 478 479 480 481 482 483 484

    /** @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);

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

501 502 503
    /** @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
504 505 506
    void startLowBattAlarm();
    void stopLowBattAlarm();

507 508
    /** @brief Arm system */
    void armSystem();
pixhawk's avatar
pixhawk committed
509
    /** @brief Disable the motors */
510
    void disarmSystem();
pixhawk's avatar
pixhawk committed
511 512 513 514 515 516

    /** @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
517
    /** @brief Add a link associated with this robot */
pixhawk's avatar
pixhawk committed
518
    void addLink(LinkInterface* link);
519 520
    /** @brief Remove a link associated with this robot */
    void removeLink(QObject* object);
pixhawk's avatar
pixhawk committed
521 522

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

525 526 527 528 529
#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
530 531 532 533 534
    /** @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);

535 536 537
    /** @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
538 539 540 541
    /** @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
542
    void setMode(int mode);
pixhawk's avatar
pixhawk committed
543

544 545 546
    /** @brief Request all parameters */
    void requestParameters();

547
    /** @brief Request a single parameter by name */
548
    void requestParameter(int component, const QString& parameter);
549
    /** @brief Request a single parameter by index */
550
    void requestParameter(int component, int id);
551

552
    /** @brief Set a system parameter */
553
    void setParameter(const int component, const QString& id, const QVariant& value);
554 555

    /** @brief Write parameters to permanent storage */
556 557 558
    void writeParametersToStorage();
    /** @brief Read parameters from permanent storage */
    void readParametersFromStorage();
559

560 561 562 563 564 565
    /** @brief Get the names of all parameters */
    QList<QString> getParameterNames(int component);

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

566 567 568 569 570
    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
571
    //void enableRawSensorFusionTransmission(int rate);
572 573 574 575
    void enablePositionTransmission(int rate);
    void enableExtra1Transmission(int rate);
    void enableExtra2Transmission(int rate);
    void enableExtra3Transmission(int rate);
lm's avatar
lm committed
576

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

580 581
    /** @brief Set world frame origin at current GPS position */
    void setLocalOriginAtCurrentGPSPosition();
582 583
    /** @brief Set world frame origin / home position at this GPS position */
    void setHomePosition(double lat, double lon, double alt);
pixhawk's avatar
pixhawk committed
584 585
    /** @brief Set local position setpoint */
    void setLocalPositionSetpoint(float x, float y, float z, float yaw);
pixhawk's avatar
pixhawk committed
586 587 588 589 590 591 592
    /** @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
593

lm's avatar
lm committed
594 595 596
    void startDataRecording();
    void stopDataRecording();

pixhawk's avatar
pixhawk committed
597 598 599
signals:

    /** @brief The main/battery voltage has changed/was updated */
600
    //void voltageChanged(int uasId, double voltage); // Defined in UASInterface already
pixhawk's avatar
pixhawk committed
601
    /** @brief An actuator value has changed */
602
    //void actuatorChanged(UASInterface*, int actId, double value); // Defined in UASInterface already
pixhawk's avatar
pixhawk committed
603 604 605 606 607 608
    /** @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 */
609
    //void heartbeat(UASInterface* uas); // Defined in UASInterface already
610
    void imageStarted(quint64 timestamp);
611 612
    /** @brief A new camera image has arrived */
    void imageReady(UASInterface* uas);
613
#if defined(QGC_PROTOBUF_ENABLED) && defined(QGC_USE_PIXHAWK_MESSAGES)
614 615 616 617
    /** @brief Point cloud data has been changed */
    void pointCloudChanged(UASInterface* uas);
    /** @brief RGBD image data has been changed */
    void rgbdImageChanged(UASInterface* uas);
618 619
    /** @brief Obstacle list data has been changed */
    void obstacleListChanged(UASInterface* uas);
620 621
    /** @brief Path data has been changed */
    void pathChanged(UASInterface* uas);
622
#endif
lm's avatar
lm committed
623 624
    /** @brief HIL controls have changed */
    void hilControlsChanged(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode);
625

626
protected:
627
    /** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
628
    quint64 getUnixTime(quint64 time=0);
629 630
    /** @brief Get the UNIX timestamp in milliseconds, enter milliseconds */
    quint64 getUnixTimeFromMs(quint64 time);
LM's avatar
LM committed
631 632
    /** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
    quint64 getUnixReferenceTime(quint64 time);
633 634
    int componentID[256];
    bool componentMulti[256];
635 636

protected slots:
637 638 639 640
    /** @brief Write settings to disk */
    void writeSettings();
    /** @brief Read settings from disk */
    void readSettings();
641

642 643 644
//    // MESSAGE RECEPTION
//    /** @brief Receive a named value message */
//    void receiveMessageNamedValue(const mavlink_message_t& message);
645 646

private:
647
//    unsigned int mode;          ///< The current mode of the MAV
pixhawk's avatar
pixhawk committed
648 649 650 651
};


#endif // _UAS_H_