UAS.h 17.4 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;
pixhawk's avatar
pixhawk committed
76
    /** @brief Get the unique system id */
77
    int getUASID() const;
78
    /** @brief Get the airframe */
79 80 81
    int getAirframe() const {
        return airframe;
    }
pixhawk's avatar
pixhawk committed
82
    /** @brief The time interval the robot is switched on */
83
    quint64 getUptime() const;
pixhawk's avatar
pixhawk committed
84
    /** @brief Get the status flag for the communication */
85
    int getCommunicationStatus() const;
pixhawk's avatar
pixhawk committed
86
    /** @brief Add one measurement and get low-passed voltage */
87
    float filterVoltage(float value) const;
pixhawk's avatar
pixhawk committed
88 89 90
    /** @brief Get the links associated with this robot */
    QList<LinkInterface*>* getLinks();

91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118
    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;
    }

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

121
    friend class UASWaypointManager;
122

INIDETAM's avatar
INIDETAM committed
123
protected: //COMMENTS FOR TEST UNIT
124
    int uasId;                    ///< Unique system ID
125
    unsigned char type;           ///< UAS type (from type enum)
pixhawk's avatar
pixhawk committed
126 127 128
    quint64 startTime;            ///< The time the UAS was switched on
    CommStatus commStatus;        ///< Communication status
    QString name;                 ///< Human-friendly name of the vehicle, e.g. bravo
129
    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
130
    QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
131
    QList<int> unknownPackets;    ///< Packet IDs which are unknown and have been received
132
    MAVLinkProtocol* mavlink;     ///< Reference to the MAVLink instance
pixhawk's avatar
pixhawk committed
133 134
    BatteryType batteryType;      ///< The battery type
    int cells;                    ///< Number of cells
pixhawk's avatar
pixhawk committed
135

136 137
    UASWaypointManager waypointManager;

pixhawk's avatar
pixhawk committed
138 139 140 141 142 143
    QList<double> actuatorValues;
    QList<QString> actuatorNames;

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

pixhawk's avatar
pixhawk committed
144 145
    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
146 147

    // Battery stats
148 149 150
    float fullVoltage;          ///< Voltage of the fully charged battery (100%)
    float emptyVoltage;         ///< Voltage of the empty battery (0%)
    float startVoltage;         ///< Voltage at system start
151
    float warnVoltage;          ///< Voltage where QGC will start to warn about low battery
152
    float warnLevelPercent;     ///< Warning level, in percent
pixhawk's avatar
pixhawk committed
153 154
    double currentVoltage;      ///< Voltage currently measured
    float lpVoltage;            ///< Low-pass filtered voltage
155 156
    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
157
    int timeRemaining;          ///< Remaining time calculated based on previous and current
158
    int mode;                   ///< The current mode of the MAV
pixhawk's avatar
pixhawk committed
159
    int status;                 ///< The current status of the MAV
160
    int navMode;                ///< The current navigation mode of the MAV
pixhawk's avatar
pixhawk committed
161 162
    quint64 onboardTimeOffset;

pixhawk's avatar
pixhawk committed
163 164 165 166 167 168 169 170 171
    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
172 173
    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
174
    bool lowBattAlarm;          ///< Switch if battery is low
175
    bool positionLock;          ///< Status if position information is available or not
lm's avatar
lm committed
176 177 178
    double localX;
    double localY;
    double localZ;
179 180 181
    double latitude;
    double longitude;
    double altitude;
182 183 184
    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
185 186 187
    double roll;
    double pitch;
    double yaw;
188
    quint64 lastHeartbeat;      ///< Time of the last heartbeat message
189
    QTimer* statusTimeout;      ///< Timer for various status timeouts
190 191 192 193 194

    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
195 196
    int imageQuality;           ///< Quality of the transmitted image (percentage)
    int imageType;              ///< Type of the transmitted image (BMP, PNG, JPEG, RAW 8 bit, RAW 32 bit)
197 198 199 200
    QByteArray imageRecBuffer;  ///< Buffer for the incoming bytestream
    QImage image;               ///< Image data of last completely transmitted image
    quint64 imageStart;

201 202
    QMap<int, QMap<QString, float>* > parameters; ///< All parameters
    bool paramsOnceRequested;   ///< If the parameter list has been read at least once
203
    int airframe;               ///< The airframe type
lm's avatar
lm committed
204
    bool attitudeKnown;         ///< True if attitude was received, false else
205
    QGCUASParamManager* paramManager; ///< Parameter manager class
206 207
    QString shortStateText;     ///< Short textual state description
    QString shortModeText;      ///< Short textual mode description
LM's avatar
LM committed
208 209
    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
lm's avatar
lm committed
210
    QGCFlightGearLink* simulation; ///< Hardware in the loop simulation link
lm's avatar
lm committed
211

212
public:
pixhawk's avatar
pixhawk committed
213 214 215 216 217
    /** @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 */
218
    float getChargeLevel();
pixhawk's avatar
pixhawk committed
219 220
    /** @brief Get the human-readable status message for this code */
    void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription);
221 222
    /** @brief Get the human-readable navigation mode translation for this mode */
    QString getNavModeText(int mode);
pixhawk's avatar
pixhawk committed
223 224 225
    /** @brief Check if vehicle is in autonomous mode */
    bool isAuto();

226 227 228
    UASWaypointManager* getWaypointManager() {
        return &waypointManager;
    }
229
    /** @brief Get reference to the param manager **/
230 231 232
    QGCUASParamManager* getParamManager() const {
        return paramManager;
    }
233 234
    // TODO Will be removed
    /** @brief Set reference to the param manager **/
235 236 237
    void setParamManager(QGCUASParamManager* manager) {
        paramManager = manager;
    }
238
    int getSystemType();
239
    QImage getImage();
240
    void requestImage();
241 242 243
    int getAutopilotType() {
        return autopilot;
    }
244

pixhawk's avatar
pixhawk committed
245
public slots:
246
    /** @brief Set the autopilot type */
247 248 249 250
    void setAutopilotType(int apType) {
        autopilot = apType;
        emit systemSpecsChanged(uasId);
    }
251
    /** @brief Set the type of airframe */
252
    void setSystemType(int systemType);
253
    /** @brief Set the specific airframe type */
254 255 256 257
    void setAirframe(int airframe) {
        this->airframe = airframe;
        emit systemSpecsChanged(uasId);
    }
258 259
    /** @brief Set a new name **/
    void setUASName(const QString& name);
lm's avatar
lm committed
260 261
    /** @brief Executes a command **/
    void executeCommand(MAV_CMD command);
262 263
    /** @brief Executes a command **/
    void executeCommand(MAV_CMD command, int confirmation, float param1, float param2, float param3, float param4, int component);
264 265 266 267
    /** @brief Set the current battery type and voltages */
    void setBatterySpecs(const QString& specs);
    /** @brief Get the current battery type and specs */
    QString getBatterySpecs();
268

pixhawk's avatar
pixhawk committed
269 270
    /** @brief Launches the system **/
    void launch();
lm's avatar
lm committed
271
    /** @brief Write this waypoint to the list of waypoints */
272
    //void setWaypoint(Waypoint* wp); FIXME tbd
lm's avatar
lm committed
273
    /** @brief Set currently active waypoint */
274
    //void setWaypointActive(int id); FIXME tbd
pixhawk's avatar
pixhawk committed
275 276 277 278
    /** @brief Order the robot to return home / to land on the runway **/
    void home();
    void halt();
    void go();
lm's avatar
lm committed
279 280 281 282 283 284 285 286 287 288

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

289 290 291 292 293 294 295
    /** @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
296 297 298 299 300 301 302 303 304
    /** @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();

305 306 307
    /** @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
308 309 310
    void startLowBattAlarm();
    void stopLowBattAlarm();

311 312
    //void requestWaypoints();  FIXME tbd
    //void clearWaypointList();   FIXME tbd
313

pixhawk's avatar
pixhawk committed
314 315 316 317 318 319 320 321 322 323
    /** @brief Enable the motors */
    void enable_motors();
    /** @brief Disable the motors */
    void disable_motors();

    /** @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
324
    /** @brief Add a link associated with this robot */
pixhawk's avatar
pixhawk committed
325
    void addLink(LinkInterface* link);
326 327
    /** @brief Remove a link associated with this robot */
    void removeLink(QObject* object);
pixhawk's avatar
pixhawk committed
328 329

    /** @brief Receive a message from one of the communication links. */
330
    virtual void receiveMessage(LinkInterface* link, mavlink_message_t message);
pixhawk's avatar
pixhawk committed
331 332 333 334 335 336

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

337 338 339
    /** @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
340 341 342 343
    /** @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
344
    void setMode(int mode);
pixhawk's avatar
pixhawk committed
345

346 347 348
    /** @brief Request all parameters */
    void requestParameters();

349 350 351
    /** @brief Request a single parameter by index */
    void requestParameter(int component, int parameter);

352
    /** @brief Set a system parameter */
lm's avatar
lm committed
353
    void setParameter(const int component, const QString& id, const float value);
354 355

    /** @brief Write parameters to permanent storage */
356 357 358
    void writeParametersToStorage();
    /** @brief Read parameters from permanent storage */
    void readParametersFromStorage();
359

360 361 362 363 364 365
    /** @brief Get the names of all parameters */
    QList<QString> getParameterNames(int component);

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

366 367 368 369 370
    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
371
    //void enableRawSensorFusionTransmission(int rate);
372 373 374 375
    void enablePositionTransmission(int rate);
    void enableExtra1Transmission(int rate);
    void enableExtra2Transmission(int rate);
    void enableExtra3Transmission(int rate);
lm's avatar
lm committed
376

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

380 381
    /** @brief Set world frame origin at current GPS position */
    void setLocalOriginAtCurrentGPSPosition();
382 383
    /** @brief Set world frame origin / home position at this GPS position */
    void setHomePosition(double lat, double lon, double alt);
pixhawk's avatar
pixhawk committed
384 385
    /** @brief Set local position setpoint */
    void setLocalPositionSetpoint(float x, float y, float z, float yaw);
pixhawk's avatar
pixhawk committed
386 387 388 389 390 391 392
    /** @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
393

lm's avatar
lm committed
394 395 396
    void startDataRecording();
    void stopDataRecording();

pixhawk's avatar
pixhawk committed
397 398 399 400 401 402 403 404 405 406 407 408 409
signals:

    /** @brief The main/battery voltage has changed/was updated */
    void voltageChanged(int uasId, double voltage);
    /** @brief An actuator value has changed */
    void actuatorChanged(UASInterface*, int actId, double value);
    /** @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);
410
    void imageStarted(quint64 timestamp);
411 412
    /** @brief A new camera image has arrived */
    void imageReady(UASInterface* uas);
lm's avatar
lm committed
413 414
    /** @brief HIL controls have changed */
    void hilControlsChanged(uint64_t time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, uint8_t systemMode, uint8_t navMode);
415

416
protected:
417 418
    /** @brief Get the UNIX timestamp in milliseconds */
    quint64 getUnixTime(quint64 time=0);
LM's avatar
LM committed
419 420
    /** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
    quint64 getUnixReferenceTime(quint64 time);
421 422

protected slots:
423 424 425 426
    /** @brief Write settings to disk */
    void writeSettings();
    /** @brief Read settings from disk */
    void readSettings();
427 428 429 430

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

private:
433
//    unsigned int mode;          ///< The current mode of the MAV
pixhawk's avatar
pixhawk committed
434 435 436 437
};


#endif // _UAS_H_