UAS.h 16.8 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"
pixhawk's avatar
pixhawk committed
39 40 41 42 43 44 45 46 47

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

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

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

    /* MANAGEMENT */

    /** @brief The name of the robot */
70
    QString getUASName(void) const;
71 72 73 74
    /** @brief Get short state */
    const QString& getShortState() const;
    /** @brief Get short mode */
    const QString& getShortMode() const;
pixhawk's avatar
pixhawk committed
75
    /** @brief Get the unique system id */
76
    int getUASID() const;
77
    /** @brief Get the airframe */
78 79 80
    int getAirframe() const {
        return airframe;
    }
pixhawk's avatar
pixhawk committed
81
    /** @brief The time interval the robot is switched on */
82
    quint64 getUptime() const;
pixhawk's avatar
pixhawk committed
83
    /** @brief Get the status flag for the communication */
84
    int getCommunicationStatus() const;
pixhawk's avatar
pixhawk committed
85
    /** @brief Add one measurement and get low-passed voltage */
86
    float filterVoltage(float value) const;
pixhawk's avatar
pixhawk committed
87 88 89
    /** @brief Get the links associated with this robot */
    QList<LinkInterface*>* getLinks();

90 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
    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;
    }
118
    bool getSelected() const;
lm's avatar
lm committed
119

120
    friend class UASWaypointManager;
121

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

135 136
    UASWaypointManager waypointManager;

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

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

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

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

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

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

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

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

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

pixhawk's avatar
pixhawk committed
243
public slots:
244
    /** @brief Set the autopilot type */
245 246 247 248
    void setAutopilotType(int apType) {
        autopilot = apType;
        emit systemSpecsChanged(uasId);
    }
249
    /** @brief Set the type of airframe */
250
    void setSystemType(int systemType);
251
    /** @brief Set the specific airframe type */
252 253 254 255
    void setAirframe(int airframe) {
        this->airframe = airframe;
        emit systemSpecsChanged(uasId);
    }
256 257 258
    /** @brief Set a new name **/
    void setUASName(const QString& name);
    /** @brief Executes an action **/
259
    void setAction(MAV_ACTION action);
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();
279 280 281 282 283 284 285
    /** @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
286 287 288 289 290 291 292 293 294
    /** @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();

295 296 297
    /** @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
298 299 300
    void startLowBattAlarm();
    void stopLowBattAlarm();

301 302
    //void requestWaypoints();  FIXME tbd
    //void clearWaypointList();   FIXME tbd
303

pixhawk's avatar
pixhawk committed
304 305 306 307 308 309 310 311 312 313
    /** @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
314
    /** @brief Add a link associated with this robot */
pixhawk's avatar
pixhawk committed
315
    void addLink(LinkInterface* link);
316 317
    /** @brief Remove a link associated with this robot */
    void removeLink(QObject* object);
pixhawk's avatar
pixhawk committed
318 319

    /** @brief Receive a message from one of the communication links. */
320
    virtual void receiveMessage(LinkInterface* link, mavlink_message_t message);
pixhawk's avatar
pixhawk committed
321 322 323 324 325 326

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

327 328 329
    /** @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
330 331 332 333
    /** @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
334
    void setMode(int mode);
pixhawk's avatar
pixhawk committed
335

336 337 338
    /** @brief Request all parameters */
    void requestParameters();

339 340 341
    /** @brief Request a single parameter by index */
    void requestParameter(int component, int parameter);

342
    /** @brief Set a system parameter */
lm's avatar
lm committed
343
    void setParameter(const int component, const QString& id, const float value);
344 345

    /** @brief Write parameters to permanent storage */
346 347 348
    void writeParametersToStorage();
    /** @brief Read parameters from permanent storage */
    void readParametersFromStorage();
349

350 351 352 353 354 355
    /** @brief Get the names of all parameters */
    QList<QString> getParameterNames(int component);

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

356 357 358 359 360
    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
361
    //void enableRawSensorFusionTransmission(int rate);
362 363 364 365
    void enablePositionTransmission(int rate);
    void enableExtra1Transmission(int rate);
    void enableExtra2Transmission(int rate);
    void enableExtra3Transmission(int rate);
lm's avatar
lm committed
366

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

370 371
    /** @brief Set world frame origin at current GPS position */
    void setLocalOriginAtCurrentGPSPosition();
372 373
    /** @brief Set world frame origin / home position at this GPS position */
    void setHomePosition(double lat, double lon, double alt);
pixhawk's avatar
pixhawk committed
374 375
    /** @brief Set local position setpoint */
    void setLocalPositionSetpoint(float x, float y, float z, float yaw);
pixhawk's avatar
pixhawk committed
376 377 378 379 380 381 382
    /** @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
383

lm's avatar
lm committed
384 385 386 387
    void startDataRecording();
    void pauseDataRecording();
    void stopDataRecording();

pixhawk's avatar
pixhawk committed
388 389 390 391 392 393 394 395 396 397 398 399 400
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);
401
    void imageStarted(quint64 timestamp);
402 403
    /** @brief A new camera image has arrived */
    void imageReady(UASInterface* uas);
404

405
protected:
406 407
    /** @brief Get the UNIX timestamp in milliseconds */
    quint64 getUnixTime(quint64 time=0);
LM's avatar
LM committed
408 409
    /** @brief Get the UNIX timestamp in milliseconds, ignore attitudeStamped mode */
    quint64 getUnixReferenceTime(quint64 time);
410 411

protected slots:
412 413 414 415
    /** @brief Write settings to disk */
    void writeSettings();
    /** @brief Read settings from disk */
    void readSettings();
416 417 418 419

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

private:
422
//    unsigned int mode;          ///< The current mode of the MAV
pixhawk's avatar
pixhawk committed
423 424 425 426
};


#endif // _UAS_H_