UAS.h 22.1 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;
    }
pixhawk's avatar
pixhawk committed
84
    /** @brief The time interval the robot is switched on */
85
    quint64 getUptime() const;
pixhawk's avatar
pixhawk committed
86
    /** @brief Get the status flag for the communication */
87
    int getCommunicationStatus() const;
pixhawk's avatar
pixhawk committed
88
    /** @brief Add one measurement and get low-passed voltage */
89
    float filterVoltage(float value) const;
pixhawk's avatar
pixhawk committed
90 91 92
    /** @brief Get the links associated with this robot */
    QList<LinkInterface*>* getLinks();

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

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

131 132 133 134
#ifdef QGC_PROTOBUF_ENABLED
    px::PointCloudXYZRGB getPointCloud() const {
        return pointCloud;
    }
135 136 137 138

    px::RGBDImage getRGBDImage() const {
        return rgbdImage;
    }
139 140
#endif

141
    friend class UASWaypointManager;
142

INIDETAM's avatar
INIDETAM committed
143
protected: //COMMENTS FOR TEST UNIT
144
    int uasId;                    ///< Unique system ID
145
    unsigned char type;           ///< UAS type (from type enum)
pixhawk's avatar
pixhawk committed
146 147 148
    quint64 startTime;            ///< The time the UAS was switched on
    CommStatus commStatus;        ///< Communication status
    QString name;                 ///< Human-friendly name of the vehicle, e.g. bravo
149
    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
150
    QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
151
    QList<int> unknownPackets;    ///< Packet IDs which are unknown and have been received
152
    MAVLinkProtocol* mavlink;     ///< Reference to the MAVLink instance
pixhawk's avatar
pixhawk committed
153 154
    BatteryType batteryType;      ///< The battery type
    int cells;                    ///< Number of cells
pixhawk's avatar
pixhawk committed
155

156 157
    UASWaypointManager waypointManager;

pixhawk's avatar
pixhawk committed
158 159 160 161 162 163
    QList<double> actuatorValues;
    QList<QString> actuatorNames;

    QList<double> motorValues;
    QList<QString> motorNames;

pixhawk's avatar
pixhawk committed
164 165
    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
166 167

    // Battery stats
168 169 170
    float fullVoltage;          ///< Voltage of the fully charged battery (100%)
    float emptyVoltage;         ///< Voltage of the empty battery (0%)
    float startVoltage;         ///< Voltage at system start
171
    float warnVoltage;          ///< Voltage where QGC will start to warn about low battery
172
    float warnLevelPercent;     ///< Warning level, in percent
pixhawk's avatar
pixhawk committed
173 174
    double currentVoltage;      ///< Voltage currently measured
    float lpVoltage;            ///< Low-pass filtered voltage
175 176
    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
177
    int timeRemaining;          ///< Remaining time calculated based on previous and current
LM's avatar
LM committed
178
    uint8_t mode;                   ///< The current mode of the MAV
pixhawk's avatar
pixhawk committed
179
    int status;                 ///< The current status of the MAV
180
    uint32_t navMode;                ///< The current navigation mode of the MAV
pixhawk's avatar
pixhawk committed
181 182
    quint64 onboardTimeOffset;

pixhawk's avatar
pixhawk committed
183 184 185 186 187 188 189 190 191
    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
192 193
    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
194
    bool lowBattAlarm;          ///< Switch if battery is low
195
    bool positionLock;          ///< Status if position information is available or not
lm's avatar
lm committed
196 197 198
    double localX;
    double localY;
    double localZ;
199 200 201
    double latitude;
    double longitude;
    double altitude;
202 203 204
    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
205 206 207
    double roll;
    double pitch;
    double yaw;
208
    quint64 lastHeartbeat;      ///< Time of the last heartbeat message
209
    QTimer* statusTimeout;      ///< Timer for various status timeouts
210 211 212 213 214

    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
215 216
    int imageQuality;           ///< Quality of the transmitted image (percentage)
    int imageType;              ///< Type of the transmitted image (BMP, PNG, JPEG, RAW 8 bit, RAW 32 bit)
217 218 219 220
    QByteArray imageRecBuffer;  ///< Buffer for the incoming bytestream
    QImage image;               ///< Image data of last completely transmitted image
    quint64 imageStart;

221 222
#ifdef QGC_PROTOBUF_ENABLED
    px::PointCloudXYZRGB pointCloud;
223
    px::RGBDImage rgbdImage;
224 225
#endif

226
    QMap<int, QMap<QString, QVariant>* > parameters; ///< All parameters
lm's avatar
lm committed
227 228 229
    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
230
    QGCUASParamManager* paramManager; ///< Parameter manager class
lm's avatar
lm committed
231 232 233 234 235 236 237
    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
238
    bool systemIsArmed;             ///< If the system is armed
lm's avatar
lm committed
239

240
public:
pixhawk's avatar
pixhawk committed
241 242 243 244 245
    /** @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 */
246
    float getChargeLevel();
pixhawk's avatar
pixhawk committed
247 248
    /** @brief Get the human-readable status message for this code */
    void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription);
249 250
    /** @brief Get the human-readable navigation mode translation for this mode */
    QString getNavModeText(int mode);
pixhawk's avatar
pixhawk committed
251 252
    /** @brief Check if vehicle is in autonomous mode */
    bool isAuto();
253 254
    /** @brief Check if vehicle is armed */
    bool isArmed() const { return systemIsArmed; }
pixhawk's avatar
pixhawk committed
255

256 257 258
    UASWaypointManager* getWaypointManager() {
        return &waypointManager;
    }
259
    /** @brief Get reference to the param manager **/
260 261 262
    QGCUASParamManager* getParamManager() const {
        return paramManager;
    }
263 264
    // TODO Will be removed
    /** @brief Set reference to the param manager **/
265 266 267
    void setParamManager(QGCUASParamManager* manager) {
        paramManager = manager;
    }
268
    int getSystemType();
lm's avatar
lm committed
269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329
    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;
        }
    }

330
    QImage getImage();
331
    void requestImage();
332 333 334
    int getAutopilotType() {
        return autopilot;
    }
lm's avatar
lm committed
335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353
    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
354 355
        case MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY:
            return "GENERIC_WAYPOINTS_ONLY";
lm's avatar
lm committed
356
            break;
lm's avatar
lm committed
357
        case MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY:
lm's avatar
lm committed
358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379
            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;
        }
    }
380

pixhawk's avatar
pixhawk committed
381
public slots:
382
    /** @brief Set the autopilot type */
lm's avatar
lm committed
383 384
    void setAutopilotType(int apType)
    {
385 386 387
        autopilot = apType;
        emit systemSpecsChanged(uasId);
    }
388
    /** @brief Set the type of airframe */
389
    void setSystemType(int systemType);
390
    /** @brief Set the specific airframe type */
lm's avatar
lm committed
391 392
    void setAirframe(int airframe)
    {
393 394 395
        this->airframe = airframe;
        emit systemSpecsChanged(uasId);
    }
396 397
    /** @brief Set a new name **/
    void setUASName(const QString& name);
lm's avatar
lm committed
398 399
    /** @brief Executes a command **/
    void executeCommand(MAV_CMD command);
400 401
    /** @brief Executes a command **/
    void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component);
402 403
    /** @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);
404 405 406 407
    /** @brief Set the current battery type and voltages */
    void setBatterySpecs(const QString& specs);
    /** @brief Get the current battery type and specs */
    QString getBatterySpecs();
408

pixhawk's avatar
pixhawk committed
409 410
    /** @brief Launches the system **/
    void launch();
lm's avatar
lm committed
411
    /** @brief Write this waypoint to the list of waypoints */
412
    //void setWaypoint(Waypoint* wp); FIXME tbd
lm's avatar
lm committed
413
    /** @brief Set currently active waypoint */
414
    //void setWaypointActive(int id); FIXME tbd
pixhawk's avatar
pixhawk committed
415 416 417 418
    /** @brief Order the robot to return home / to land on the runway **/
    void home();
    void halt();
    void go();
lm's avatar
lm committed
419 420 421 422 423 424 425 426 427 428

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

429 430 431 432 433 434 435
    /** @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
436 437 438 439 440 441 442 443 444
    /** @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();

445 446 447
    /** @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
448 449 450
    void startLowBattAlarm();
    void stopLowBattAlarm();

451 452
    /** @brief Arm system */
    void armSystem();
pixhawk's avatar
pixhawk committed
453
    /** @brief Disable the motors */
454
    void disarmSystem();
pixhawk's avatar
pixhawk committed
455 456 457 458 459 460

    /** @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
461
    /** @brief Add a link associated with this robot */
pixhawk's avatar
pixhawk committed
462
    void addLink(LinkInterface* link);
463 464
    /** @brief Remove a link associated with this robot */
    void removeLink(QObject* object);
pixhawk's avatar
pixhawk committed
465 466

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

469 470 471 472 473
#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
474 475 476 477 478
    /** @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);

479 480 481
    /** @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
482 483 484 485
    /** @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
486
    void setMode(int mode);
pixhawk's avatar
pixhawk committed
487

488 489 490
    /** @brief Request all parameters */
    void requestParameters();

491
    /** @brief Request a single parameter by name */
492
    void requestParameter(int component, const QString& parameter);
493
    /** @brief Request a single parameter by index */
494
    void requestParameter(int component, int id);
495

496
    /** @brief Set a system parameter */
497
    void setParameter(const int component, const QString& id, const QVariant& value);
498 499

    /** @brief Write parameters to permanent storage */
500 501 502
    void writeParametersToStorage();
    /** @brief Read parameters from permanent storage */
    void readParametersFromStorage();
503

504 505 506 507 508 509
    /** @brief Get the names of all parameters */
    QList<QString> getParameterNames(int component);

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

510 511 512 513 514
    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
515
    //void enableRawSensorFusionTransmission(int rate);
516 517 518 519
    void enablePositionTransmission(int rate);
    void enableExtra1Transmission(int rate);
    void enableExtra2Transmission(int rate);
    void enableExtra3Transmission(int rate);
lm's avatar
lm committed
520

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

524 525
    /** @brief Set world frame origin at current GPS position */
    void setLocalOriginAtCurrentGPSPosition();
526 527
    /** @brief Set world frame origin / home position at this GPS position */
    void setHomePosition(double lat, double lon, double alt);
pixhawk's avatar
pixhawk committed
528 529
    /** @brief Set local position setpoint */
    void setLocalPositionSetpoint(float x, float y, float z, float yaw);
pixhawk's avatar
pixhawk committed
530 531 532 533 534 535 536
    /** @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
537

lm's avatar
lm committed
538 539 540
    void startDataRecording();
    void stopDataRecording();

pixhawk's avatar
pixhawk committed
541 542 543
signals:

    /** @brief The main/battery voltage has changed/was updated */
544
    //void voltageChanged(int uasId, double voltage); // Defined in UASInterface already
pixhawk's avatar
pixhawk committed
545
    /** @brief An actuator value has changed */
546
    //void actuatorChanged(UASInterface*, int actId, double value); // Defined in UASInterface already
pixhawk's avatar
pixhawk committed
547 548 549 550 551 552
    /** @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 */
553
    //void heartbeat(UASInterface* uas); // Defined in UASInterface already
554
    void imageStarted(quint64 timestamp);
555 556
    /** @brief A new camera image has arrived */
    void imageReady(UASInterface* uas);
557 558 559 560
    /** @brief Point cloud data has been changed */
    void pointCloudChanged(UASInterface* uas);
    /** @brief RGBD image data has been changed */
    void rgbdImageChanged(UASInterface* uas);
lm's avatar
lm committed
561 562
    /** @brief HIL controls have changed */
    void hilControlsChanged(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode);
563

564
protected:
565
    /** @brief Get the UNIX timestamp in milliseconds, enter microseconds */
566
    quint64 getUnixTime(quint64 time=0);
567 568
    /** @brief Get the UNIX timestamp in milliseconds, enter milliseconds */
    quint64 getUnixTimeFromMs(quint64 time);
LM's avatar
LM committed
569 570
    /** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
    quint64 getUnixReferenceTime(quint64 time);
571 572
    int componentID[256];
    bool componentMulti[256];
573 574

protected slots:
575 576 577 578
    /** @brief Write settings to disk */
    void writeSettings();
    /** @brief Read settings from disk */
    void readSettings();
579 580 581 582

    // MESSAGE RECEPTION
    /** @brief Receive a named value message */
    void receiveMessageNamedValue(const mavlink_message_t& message);
583 584

private:
585
//    unsigned int mode;          ///< The current mode of the MAV
pixhawk's avatar
pixhawk committed
586 587 588 589
};


#endif // _UAS_H_