UAS.h 35.7 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
39
40
/*=====================================================================

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"
#include "QGCHilLink.h"
#include "QGCFlightGearLink.h"
41
#include "QGCJSBSimLink.h"
42
#include "QGCXPlaneLink.h"
43
#include "FileManager.h"
44

45
Q_DECLARE_LOGGING_CATEGORY(UASLog)
tstellanova's avatar
tstellanova committed
46

47
48
49
50
51
52
53
54
55
56
57
58
/**
 * @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:
59
    UAS(MAVLinkProtocol* protocol, int id = 0);
60
61
    ~UAS();

62
63
    float lipoFull;  ///< 100% charged voltage
    float lipoEmpty; ///< Discharged voltage
64
65
66
67
68
69
70
71
72
73

    /* MANAGEMENT */

    /** @brief The name of the robot */
    QString getUASName(void) const;
    /** @brief Get short state */
    const QString& getShortState() const;
    /** @brief Get short mode */
    const QString& getShortMode() const;
    /** @brief Translate from mode id to text */
74
    QString getShortModeTextFor(uint8_t base_mode, uint32_t custom_mode) const;
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
    /** @brief Translate from mode id to audio text */
    static QString getAudioModeTextFor(int id);
    /** @brief Get the unique system id */
    int getUASID() const;
    /** @brief Get the airframe */
    int getAirframe() const
    {
        return airframe;
    }
    /** @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 */
    float filterVoltage(float value) const;
    /** @brief Get the links associated with this robot */
92
    QList<LinkInterface*> getLinks();
93

94
95
96
97
98
    Q_PROPERTY(double localX READ getLocalX WRITE setLocalX NOTIFY localXChanged)
    Q_PROPERTY(double localY READ getLocalY WRITE setLocalY NOTIFY localYChanged)
    Q_PROPERTY(double localZ READ getLocalZ WRITE setLocalZ NOTIFY localZChanged)
    Q_PROPERTY(double latitude READ getLatitude WRITE setLatitude NOTIFY latitudeChanged)
    Q_PROPERTY(double longitude READ getLongitude WRITE setLongitude NOTIFY longitudeChanged)
99
    Q_PROPERTY(double satelliteCount READ getSatelliteCount WRITE setSatelliteCount NOTIFY satelliteCountChanged)
100
101
    Q_PROPERTY(bool isLocalPositionKnown READ localPositionKnown)
    Q_PROPERTY(bool isGlobalPositionKnown READ globalPositionKnown)
102
103
104
    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)
105
    Q_PROPERTY(double distToWaypoint READ getDistToWaypoint WRITE setDistToWaypoint NOTIFY distToWaypointChanged)
106
    Q_PROPERTY(double airSpeed READ getGroundSpeed WRITE setGroundSpeed NOTIFY airSpeedChanged)
107
    Q_PROPERTY(double groundSpeed READ getGroundSpeed WRITE setGroundSpeed NOTIFY groundSpeedChanged)
108
109
    Q_PROPERTY(double bearingToWaypoint READ getBearingToWaypoint WRITE setBearingToWaypoint NOTIFY bearingToWaypointChanged)
    Q_PROPERTY(double altitudeAMSL READ getAltitudeAMSL WRITE setAltitudeAMSL NOTIFY altitudeAMSLChanged)
110
111
    Q_PROPERTY(double altitudeAMSLFT READ getAltitudeAMSLFT NOTIFY altitudeAMSLFTChanged)
    Q_PROPERTY(double altitudeWGS84 READ getAltitudeWGS84 WRITE setAltitudeWGS84 NOTIFY altitudeWGS84Changed)
112
    Q_PROPERTY(double altitudeRelative READ getAltitudeRelative WRITE setAltitudeRelative NOTIFY altitudeRelativeChanged)
113
114
115
116
117
118
119
120
121
122
123

    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;
    }
124

125
126
127
128
129
130
131
132
133
134
135
    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;
    }
136
137
138
139
140

    void setLocalX(double val)
    {
        localX = val;
        emit localXChanged(val,"localX");
141
        emit valueChanged(this->uasId,"localX","m",QVariant(val),getUnixTime());
142
    }
143

144
145
146
147
    double getLocalX() const
    {
        return localX;
    }
148
149
150
151
152

    void setLocalY(double val)
    {
        localY = val;
        emit localYChanged(val,"localY");
153
        emit valueChanged(this->uasId,"localY","m",QVariant(val),getUnixTime());
154
    }
155
156
157
158
    double getLocalY() const
    {
        return localY;
    }
159
160
161
162
163

    void setLocalZ(double val)
    {
        localZ = val;
        emit localZChanged(val,"localZ");
164
        emit valueChanged(this->uasId,"localZ","m",QVariant(val),getUnixTime());
165
    }
166
167
168
169
    double getLocalZ() const
    {
        return localZ;
    }
170
171
172
173
174

    void setLatitude(double val)
    {
        latitude = val;
        emit latitudeChanged(val,"latitude");
175
        emit valueChanged(this->uasId,"latitude","deg",QVariant(val),getUnixTime());
176
    }
177

178
179
180
181
    double getLatitude() const
    {
        return latitude;
    }
182
183
184
185
186

    void setLongitude(double val)
    {
        longitude = val;
        emit longitudeChanged(val,"longitude");
187
        emit valueChanged(this->uasId,"longitude","deg",QVariant(val),getUnixTime());
188
    }
189

190
191
192
193
    double getLongitude() const
    {
        return longitude;
    }
194

195
    void setAltitudeAMSL(double val)
196
    {
197
198
        altitudeAMSL = val;
        emit altitudeAMSLChanged(val, "altitudeAMSL");
199
200
201
202
        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());
203
204
    }

205
    double getAltitudeAMSL() const
206
    {
207
208
209
        return altitudeAMSL;
    }

210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
    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;
    }


228
229
230
231
232
233
234
235
236
237
    void setAltitudeRelative(double val)
    {
        altitudeRelative = val;
        emit altitudeRelativeChanged(val, "altitudeRelative");
        emit valueChanged(this->uasId,"altitudeRelative","m",QVariant(val),getUnixTime());
    }

    double getAltitudeRelative() const
    {
        return altitudeRelative;
238
    }
239
240
241
242
243

    void setSatelliteCount(double val)
    {
        satelliteCount = val;
        emit satelliteCountChanged(val,"satelliteCount");
244
        emit valueChanged(this->uasId,"satelliteCount","",QVariant(val),getUnixTime());
245
246
247
248
249
250
251
    }

    double getSatelliteCount() const
    {
        return satelliteCount;
    }

252
253
254
255
    virtual bool localPositionKnown() const
    {
        return isLocalPositionKnown;
    }
256

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

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

    double getDistToWaypoint() const
    {
        return distToWaypoint;
    }

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

    double getBearingToWaypoint() const
    {
        return bearingToWaypoint;
    }


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

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

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

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

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

315
316
317
318
    double getYaw() const
    {
        return yaw;
    }
319

320
321
322
323
324
325
326
327
328
329
330
    bool getSelected() const;
    QVector3D getNedPosGlobalOffset() const
    {
        return nedPosGlobalOffset;
    }

    QVector3D getNedAttGlobalOffset() const
    {
        return nedAttGlobalOffset;
    }

331
332
333
    bool isRotaryWing();
    bool isFixedWing();

334
    friend class UASWaypointManager;
335
    friend class FileManager;
336
337

protected: //COMMENTS FOR TEST UNIT
338
    /// LINK ID AND STATUS
339
    int uasId;                    ///< Unique system ID
340
    QMap<int, QString> components;///< IDs and names of all detected onboard components
341
342
343
344
345
    
    /// List of all links associated with this UAS. We keep SharedLinkInterface objects which are QSharedPointer's in order to
    /// maintain reference counts across threads. This way Link deletion works correctly.
    QList<SharedLinkInterface> _links;
    
346
347
    QList<int> unknownPackets;    ///< Packet IDs which are unknown and have been received
    MAVLinkProtocol* mavlink;     ///< Reference to the MAVLink instance
348
349
350
    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
351
    QTimer statusTimeout;       ///< Timer for various status timeouts
352

353
354
355
356
357
358
    /// BASIC UAS TYPE, NAME AND STATE
    QString name;                 ///< Human-friendly name of the vehicle, e.g. bravo
    unsigned char type;           ///< UAS type (from type enum)
    int airframe;                 ///< The airframe type
    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
    bool systemIsArmed;           ///< If the system is armed
359
    uint8_t base_mode;                 ///< The current mode of the MAV
360
361
362
363
364
365
    uint32_t custom_mode;         ///< The current mode of the MAV
    int status;                   ///< The current status of the MAV
    QString shortModeText;        ///< Short textual mode description
    QString shortStateText;       ///< Short textual state description

    /// OUTPUT
366
367
368
369
370
371
372
    QList<double> actuatorValues;
    QList<QString> actuatorNames;
    QList<double> motorValues;
    QList<QString> motorNames;
    double thrustSum;           ///< Sum of forward/up thrust of all thrust actuators, in Newtons
    double thrustMax;           ///< Maximum forward/up thrust of this vehicle, in Newtons

373
374
    // dongfang: This looks like a candidate for being moved off to a separate class.
    /// BATTERY / ENERGY
375
376
377
378
379
380
381
    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
382
    double currentCurrent;      ///< Battery current currently measured
383
384
385
    bool batteryRemainingEstimateEnabled; ///< If the estimate is enabled, QGC will try to estimate the remaining battery life
    float chargeLevel;          ///< Charge level of battery, in percent
    int timeRemaining;          ///< Remaining time calculated based on previous and current
386
387
388
389
390
    bool lowBattAlarm;          ///< Switch if battery is low


    /// TIMEKEEPING
    quint64 startTime;            ///< The time the UAS was switched on
391
392
    quint64 onboardTimeOffset;

393
    /// MANUAL CONTROL
394
395
396
397
398
399
400
401
402
    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)
403
404

    /// POSITION
405
    bool positionLock;          ///< Status if position information is available or not
406
407
    bool isLocalPositionKnown;  ///< If the local position has been received for this MAV
    bool isGlobalPositionKnown; ///< If the global position has been received for this MAV
408

409
410
411
    double localX;
    double localY;
    double localZ;
412

413
414
    double latitude;            ///< Global latitude as estimated by position estimator
    double longitude;           ///< Global longitude as estimated by position estimator
415
416
417
    double altitudeAMSL;        ///< Global altitude as estimated by position estimator, AMSL
    double altitudeAMSLFT;        ///< Global altitude as estimated by position estimator, AMSL
    double altitudeWGS84;        ///< Global altitude as estimated by position estimator, WGS84
418
    double altitudeRelative;    ///< Altitude above home as estimated by position estimator
419

420
    double satelliteCount;      ///< Number of satellites visible to raw GPS
421
422
423
424
    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
425
426
427
    double speedX;              ///< True speed in X axis
    double speedY;              ///< True speed in Y axis
    double speedZ;              ///< True speed in Z axis
428
429
430
431
432

    QVector3D nedPosGlobalOffset;   ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin
    QVector3D nedAttGlobalOffset;   ///< Offset between the system's NED position measurements and the swarm / global 0/0/0 origin

    /// WAYPOINT NAVIGATION
433
    double distToWaypoint;       ///< Distance to next waypoint
434
435
    double airSpeed;             ///< Airspeed
    double groundSpeed;          ///< Groundspeed
436
437
    double bearingToWaypoint;    ///< Bearing to next waypoint
    UASWaypointManager waypointManager;
438
    FileManager   fileManager;
439
440
441
442
443

    /// 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
444
445
446
447
    double roll;
    double pitch;
    double yaw;

448
449
    // dongfang: This looks like a candidate for being moved off to a separate class.
    /// IMAGING
450
451
452
453
454
455
456
457
458
459
460
    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;
461
    bool blockHomePositionChanges;   ///< Block changes to the home position
462
    bool receivedMode;          ///< True if mode was retrieved from current conenction to UAS
463

464
    /// SIMULATION
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
    QGCHilLink* simulation;         ///< Hardware in the loop simulation link

public:
    /** @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 */
    float getChargeLevel();
    /** @brief Get the human-readable status message for this code */
    void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription);
    /** @brief Check if vehicle is in autonomous mode */
    bool isAuto();
    /** @brief Check if vehicle is armed */
    bool isArmed() const { return systemIsArmed; }
480
    /** @brief Check if vehicle is supposed to be in HIL mode by the GS */
481
    bool isHilEnabled() const { return hilEnabled; }
482
483
    /** @brief Check if vehicle is in HIL mode */
    bool isHilActive() const { return base_mode & MAV_MODE_FLAG_HIL_ENABLED; }
484

485
    /** @brief Get reference to the waypoint manager **/
486
487
488
    UASWaypointManager* getWaypointManager() {
        return &waypointManager;
    }
489

490
    virtual FileManager* getFileManager() {
491
492
493
        return &fileManager;
    }

494
495
496
497
    /** @brief Get the HIL simulation */
    QGCHilLink* getHILSimulation() const {
        return simulation;
    }
498
499


dogmaphobic's avatar
dogmaphobic committed
500
501
    int  getSystemType();
    bool isAirplane();
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535

    /**
     * @brief Returns true for systems that can reverse. If the system has no control over position, it returns false as
     * @return If the specified vehicle type can
     */
    bool systemCanReverse() const
    {
        switch(type)
        {
        case MAV_TYPE_GENERIC:
        case MAV_TYPE_FIXED_WING:
        case MAV_TYPE_ROCKET:
        case MAV_TYPE_FLAPPING_WING:

        // System types that don't have movement
        case MAV_TYPE_ANTENNA_TRACKER:
        case MAV_TYPE_GCS:
        case MAV_TYPE_FREE_BALLOON:
        default:
            return false;
        case MAV_TYPE_QUADROTOR:
        case MAV_TYPE_COAXIAL:
        case MAV_TYPE_HELICOPTER:
        case MAV_TYPE_AIRSHIP:
        case MAV_TYPE_GROUND_ROVER:
        case MAV_TYPE_SURFACE_BOAT:
        case MAV_TYPE_SUBMARINE:
        case MAV_TYPE_HEXAROTOR:
        case MAV_TYPE_OCTOROTOR:
        case MAV_TYPE_TRICOPTER:
            return true;
        }
    }

536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
    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;
        }
    }

    QImage getImage();
    void requestImage();
    int getAutopilotType(){
        return autopilot;
    }
    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;
        case MAV_AUTOPILOT_GENERIC_WAYPOINTS_ONLY:
            return "GENERIC_WAYPOINTS_ONLY";
            break;
        case MAV_AUTOPILOT_GENERIC_WAYPOINTS_AND_SIMPLE_NAVIGATION_ONLY:
            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;
        case MAV_AUTOPILOT_PX4:
            return "PX4";
            break;
        default:
            return "";
            break;
        }
    }
650
651
652
653
654
    /** From UASInterface */
    QList<QAction*> getActions() const
    {
        return actions;
    }
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672

public slots:
    /** @brief Set the autopilot type */
    void setAutopilotType(int apType)
    {
        autopilot = apType;
        emit systemSpecsChanged(uasId);
    }
    /** @brief Set the type of airframe */
    void setSystemType(int systemType);
    /** @brief Set the specific airframe type */
    void setAirframe(int airframe)
    {
        if((airframe >= QGC_AIRFRAME_GENERIC) && (airframe < QGC_AIRFRAME_END_OF_ENUM))
        {
          this->airframe = airframe;
          emit systemSpecsChanged(uasId);
        }
673

674
675
676
677
678
679
680
    }
    /** @brief Set a new name **/
    void setUASName(const QString& name);
    /** @brief Executes a command **/
    void executeCommand(MAV_CMD command);
    /** @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);
681
682
    /** @brief Executes a command ack, with success boolean **/
    void executeCommandAck(int num, bool success);
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
    /** @brief Set the current battery type and voltages */
    void setBatterySpecs(const QString& specs);
    /** @brief Get the current battery type and specs */
    QString getBatterySpecs();

    /** @brief Launches the system **/
    void launch();
    /** @brief Write this waypoint to the list of waypoints */
    //void setWaypoint(Waypoint* wp); FIXME tbd
    /** @brief Set currently active waypoint */
    //void setWaypointActive(int id); FIXME tbd
    /** @brief Order the robot to return home **/
    void home();
    /** @brief Order the robot to land **/
    void land();
698
699
700
    /** @brief Order the robot to pair its receiver **/
    void pairRX(int rxType, int rxSubType);

701
702
703
704
    void halt();
    void go();

    /** @brief Enable / disable HIL */
705
    void enableHilFlightGear(bool enable, QString options, bool sensorHil, QObject * configuration);
706
    void enableHilJSBSim(bool enable, QString options);
707
708
709
    void enableHilXPlane(bool enable);

    /** @brief Send the full HIL state to the MAV */
710
711
    void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollRotationRate,
                        float pitchRotationRate, float yawRotationRate, double lat, double lon, double alt,
Lorenz Meier's avatar
Lorenz Meier committed
712
713
714
715
716
                        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);
717

Lorenz Meier's avatar
Lorenz Meier committed
718
    /** @brief RAW sensors for sensor HIL */
Lorenz Meier's avatar
Lorenz Meier committed
719
720
    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
721

722
723
724
725
    /** @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);

Lorenz Meier's avatar
Lorenz Meier committed
726
727
728
729
730
731
732
733
734
735
736
737
    /**
     * @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
     */
Lorenz Meier's avatar
Lorenz Meier committed
738
    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
739
740


741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
    /** @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();


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

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

    void startLowBattAlarm();
    void stopLowBattAlarm();

    /** @brief Arm system */
    void armSystem();
    /** @brief Disable the motors */
    void disarmSystem();
767
768
    /** @brief Toggle the armed state of the system. */
    void toggleArmedState();
769
770
771
772
773
774
775
776
777
778
779
780
    /**
     * @brief Tell the UAS to switch into a completely-autonomous mode, so disable manual input.
     */
    void goAutonomous();
    /**
     * @brief Tell the UAS to switch to manual control. Stabilized attitude may simultaneously be engaged.
     */
    void goManual();
    /**
     * @brief Tell the UAS to switch between manual and autonomous control.
     */
    void toggleAutonomy();
781
782

    /** @brief Set the values for the manual control of the vehicle */
783
    void setManualControlCommands(float roll, float pitch, float yaw, float thrust, qint8 xHat, qint8 yHat, quint16 buttons);
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806

    /** @brief Set the values for the 6dof manual control of the vehicle */
    void setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw);

    /** @brief Add a link associated with this robot */
    void addLink(LinkInterface* link);

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

#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

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

    /** @brief Set this UAS as the system currently in focus, e.g. in the main display widgets */
    void setSelected();

807
    /** @brief Set current mode of operation, e.g. auto or manual, always uses the current arming status for safety reason */
808
    void setMode(uint8_t newBaseMode, uint32_t newCustomMode);
809

810
811
812
    /** @brief Set current mode of operation, e.g. auto or manual, does not check the arming status, for anything else than arming/disarming operations use setMode instead */
    void setModeArm(uint8_t newBaseMode, uint32_t newCustomMode);

813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
    void enableAllDataTransmission(int rate);
    void enableRawSensorDataTransmission(int rate);
    void enableExtendedSystemStatusTransmission(int rate);
    void enableRCChannelDataTransmission(int rate);
    void enableRawControllerDataTransmission(int rate);
    //void enableRawSensorFusionTransmission(int rate);
    void enablePositionTransmission(int rate);
    void enableExtra1Transmission(int rate);
    void enableExtra2Transmission(int rate);
    void enableExtra3Transmission(int rate);

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

    /** @brief Set world frame origin at current GPS position */
    void setLocalOriginAtCurrentGPSPosition();
    /** @brief Set world frame origin / home position at this GPS position */
    void setHomePosition(double lat, double lon, double alt);
    /** @brief Set local position setpoint */
    void setLocalPositionSetpoint(float x, float y, float z, float yaw);
    /** @brief Add an offset in body frame to the setpoint */
    void setLocalPositionOffset(float x, float y, float z, float yaw);

Don Gagne's avatar
Don Gagne committed
836
837
    void startCalibration(StartCalibrationType calType);
    void stopCalibration(void);
838
839
840
841

    void startDataRecording();
    void stopDataRecording();
    void deleteSettings();
842
843
844

    /** @brief Triggers the action associated with the given ID. */
    void triggerAction(int action);
845
846

    /** @brief Send command to map a RC channel to a parameter */
Thomas Gubler's avatar
Thomas Gubler committed
847
    void sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax);
848
849
850

    /** @brief Send command to disable all bindings/maps between RC and parameters */
    void unsetRCToParameterMap();
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
signals:
    /** @brief The main/battery voltage has changed/was updated */
    //void voltageChanged(int uasId, double voltage); // Defined in UASInterface already
    /** @brief An actuator value has changed */
    //void actuatorChanged(UASInterface*, int actId, double value); // Defined in UASInterface already
    /** @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 */
    //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 */
867
    void hilControlsChanged(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode);
868
    /** @brief HIL actuator outputs have changed */
869
    void hilActuatorsChanged(quint64 time, float act1, float act2, float act3, float act4, float act5, float act6, float act7, float act8);
870

871
872
873
874
875
    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);
876
    void altitudeAMSLChanged(double val,QString name);
877
878
    void altitudeAMSLFTChanged(double val,QString name);
    void altitudeWGS84Changed(double val,QString name);
879
    void altitudeRelativeChanged(double val,QString name);
880
881
882
883
    void rollChanged(double val,QString name);
    void pitchChanged(double val,QString name);
    void yawChanged(double val,QString name);
    void satelliteCountChanged(double val,QString name);
884
    void distToWaypointChanged(double val,QString name);
885
    void groundSpeedChanged(double val, QString name);
886
    void airSpeedChanged(double val, QString name);
887
    void bearingToWaypointChanged(double val,QString name);
888
889
890
891
892
893
894
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);
895

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

898
899
900
901
902
903
904
905
    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
    bool hilEnabled;            ///< Set to true if HIL mode is enabled from GCS (UAS might be in HIL even if this flag is not set, this defines the GCS HIL setting)
906
    bool sensorHil;             ///< True if sensor HIL is enabled
907
    quint64 lastSendTimeGPS;     ///< Last HIL GPS message sent
908
909
    quint64 lastSendTimeSensors; ///< Last HIL Sensors message sent
    quint64 lastSendTimeOpticalFlow; ///< Last HIL Optical Flow message sent
910
    QList<QAction*> actions; ///< A list of actions that this UAS can perform.
911

912

913
914
915
916
917
protected slots:
    /** @brief Write settings to disk */
    void writeSettings();
    /** @brief Read settings from disk */
    void readSettings();
918
    
919
920
921
private slots:
    void _linkDisconnected(LinkInterface* link);
    
922
923
private:
    bool _containsLink(LinkInterface* link);
924
925
926
927
};


#endif // _UAS_H_