UAS.h 14.2 KB
Newer Older
1 2 3 4 5 6 7 8
/****************************************************************************
 *
 *   (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
 *
 * QGroundControl is licensed according to the terms in the file
 * COPYING.md in the root of the source code directory.
 *
 ****************************************************************************/
9

Donald Gagne's avatar
Donald Gagne committed
10 11 12
// NO NEW CODE HERE
// UASInterface, UAS.h/cc are deprecated. All new functionality should go into Vehicle.h/cc
//
13 14 15 16 17 18 19 20

#ifndef _UAS_H_
#define _UAS_H_

#include "UASInterface.h"
#include <MAVLinkProtocol.h>
#include <QVector3D>
#include "QGCMAVLink.h"
21
#include "Vehicle.h"
22
#include "FirmwarePluginManager.h"
23

dogmaphobic's avatar
dogmaphobic committed
24
#ifndef __mobile__
25
#include "FileManager.h"
26 27
#include "QGCHilLink.h"
#include "QGCFlightGearLink.h"
28
#include "QGCJSBSimLink.h"
29
#include "QGCXPlaneLink.h"
dogmaphobic's avatar
dogmaphobic committed
30
#endif
31

32
Q_DECLARE_LOGGING_CATEGORY(UASLog)
tstellanova's avatar
tstellanova committed
33

34 35
class Vehicle;

36 37 38 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.
 */
class UAS : public UASInterface
{
    Q_OBJECT
public:
48
    UAS(MAVLinkProtocol* protocol, Vehicle* vehicle, FirmwarePluginManager * firmwarePluginManager);
49

50 51
    float lipoFull;  ///< 100% charged voltage
    float lipoEmpty; ///< Discharged voltage
52 53 54 55 56 57 58 59 60 61 62

    /* MANAGEMENT */

    /** @brief Get the unique system id */
    int getUASID() const;
    /** @brief Get the components */
    QMap<int, QString> getComponents();

    /** @brief The time interval the robot is switched on */
    quint64 getUptime() const;

63 64 65
    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)
66

Don Gagne's avatar
Don Gagne committed
67 68
    /// Vehicle is about to go away
    void shutdownVehicle(void);
69

70 71 72 73 74 75
    void setRoll(double val)
    {
        roll = val;
        emit rollChanged(val,"roll");
    }

76 77 78 79
    double getRoll() const
    {
        return roll;
    }
80 81 82 83 84 85 86

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

87 88 89 90
    double getPitch() const
    {
        return pitch;
    }
91 92 93 94 95 96 97

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

98 99 100 101
    double getYaw() const
    {
        return yaw;
    }
102

103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155
    // Setters for HIL noise variance
    void setXaccVar(float var){
        xacc_var = var;
    }

    void setYaccVar(float var){
        yacc_var = var;
    }

    void setZaccVar(float var){
        zacc_var = var;
    }

    void setRollSpeedVar(float var){
        rollspeed_var = var;
    }

    void setPitchSpeedVar(float var){
        pitchspeed_var = var;
    }

    void setYawSpeedVar(float var){
        pitchspeed_var = var;
    }

    void setXmagVar(float var){
        xmag_var = var;
    }

    void setYmagVar(float var){
        ymag_var = var;
    }

    void setZmagVar(float var){
        zmag_var = var;
    }

    void setAbsPressureVar(float var){
        abs_pressure_var = var;
    }

    void setDiffPressureVar(float var){
        diff_pressure_var = var;
    }

    void setPressureAltVar(float var){
        pressure_alt_var = var;
    }

    void setTemperatureVar(float var){
        temperature_var = var;
    }

156
#ifndef __mobile__
157
    friend class FileManager;
158
#endif
159 160

protected: //COMMENTS FOR TEST UNIT
161
    /// LINK ID AND STATUS
162
    int uasId;                    ///< Unique system ID
163
    QMap<int, QString> components;///< IDs and names of all detected onboard components
164

165 166
    QList<int> unknownPackets;    ///< Packet IDs which are unknown and have been received
    MAVLinkProtocol* mavlink;     ///< Reference to the MAVLink instance
167 168
    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
169

170 171
    /// BASIC UAS TYPE, NAME AND STATE
    int status;                   ///< The current status of the MAV
172

173 174
    /// TIMEKEEPING
    quint64 startTime;            ///< The time the UAS was switched on
175 176
    quint64 onboardTimeOffset;

177
    /// MANUAL CONTROL
178 179 180 181 182 183 184 185 186
    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)
187 188

    /// POSITION
189
    bool isGlobalPositionKnown; ///< If the global position has been received for this MAV
190

191
#ifndef __mobile__
192
    FileManager   fileManager;
193
#endif
194 195 196 197 198

    /// 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
199 200 201 202
    double roll;
    double pitch;
    double yaw;

203 204
    // dongfang: This looks like a candidate for being moved off to a separate class.
    /// IMAGING
205 206
    int imageSize;              ///< Image size being transmitted (bytes)
    int imagePackets;           ///< Number of data packets being sent for this image
nopeppermint's avatar
nopeppermint committed
207
    int imagePacketsArrived;    ///< Number of data packets received
208 209 210 211 212 213 214 215
    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;
216
    bool blockHomePositionChanges;   ///< Block changes to the home position
217
    bool receivedMode;          ///< True if mode was retrieved from current conenction to UAS
218

219 220 221 222 223 224 225 226 227 228 229 230 231 232 233
    /// SIMULATION NOISE
    float xacc_var;             ///< variance of x acclerometer noise for HIL sim (mg)
    float yacc_var;             ///< variance of y acclerometer noise for HIL sim (mg)
    float zacc_var;             ///< variance of z acclerometer noise for HIL sim (mg)
    float rollspeed_var;        ///< variance of x gyroscope noise for HIL sim (rad/s)
    float pitchspeed_var;       ///< variance of y gyroscope noise for HIL sim (rad/s)
    float yawspeed_var;         ///< variance of z gyroscope noise for HIL sim (rad/s)
    float xmag_var;             ///< variance of x magnatometer noise for HIL sim (???)
    float ymag_var;             ///< variance of y magnatometer noise for HIL sim (???)
    float zmag_var;             ///< variance of z magnatometer noise for HIL sim (???)
    float abs_pressure_var;     ///< variance of absolute pressure noise for HIL sim (hPa)
    float diff_pressure_var;    ///< variance of differential pressure noise for HIL sim (hPa)
    float pressure_alt_var;     ///< variance of altitude pressure noise for HIL sim (hPa)
    float temperature_var;      ///< variance of temperature noise for HIL sim (C)

234
    /// SIMULATION
dogmaphobic's avatar
dogmaphobic committed
235
#ifndef __mobile__
236
    QGCHilLink* simulation;         ///< Hardware in the loop simulation link
dogmaphobic's avatar
dogmaphobic committed
237
#endif
238 239 240 241 242

public:
    /** @brief Get the human-readable status message for this code */
    void getStatusForCode(int statusCode, QString& uasState, QString& stateDescription);

243 244 245
#ifndef __mobile__
    virtual FileManager* getFileManager() { return &fileManager; }
#endif
246

247
    /** @brief Get the HIL simulation */
dogmaphobic's avatar
dogmaphobic committed
248
#ifndef __mobile__
249 250 251
    QGCHilLink* getHILSimulation() const {
        return simulation;
    }
dogmaphobic's avatar
dogmaphobic committed
252
#endif
253

254 255 256 257
    QImage getImage();
    void requestImage();

public slots:
258 259 260
    /** @brief Order the robot to pair its receiver **/
    void pairRX(int rxType, int rxSubType);

261
    /** @brief Enable / disable HIL */
dogmaphobic's avatar
dogmaphobic committed
262
#ifndef __mobile__
263
    void enableHilFlightGear(bool enable, QString options, bool sensorHil, QObject * configuration);
264
    void enableHilJSBSim(bool enable, QString options);
265 266 267
    void enableHilXPlane(bool enable);

    /** @brief Send the full HIL state to the MAV */
268 269
    void sendHilState(quint64 time_us, float roll, float pitch, float yaw, float rollRotationRate,
                        float pitchRotationRate, float yawRotationRate, double lat, double lon, double alt,
270 271 272 273 274
                        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);
275

Lorenz Meier's avatar
Lorenz Meier committed
276
    /** @brief RAW sensors for sensor HIL */
277 278
    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
279

280 281 282 283
    /** @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);

284 285
    float addZeroMeanNoise(float truth_meas, float noise_var);

Lorenz Meier's avatar
Lorenz Meier committed
286 287 288 289 290 291 292 293 294 295 296 297
    /**
     * @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
     */
298
    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
299 300


301 302 303 304 305
    /** @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();
dogmaphobic's avatar
dogmaphobic committed
306
#endif
307 308

    /** @brief Set the values for the manual control of the vehicle */
309
    void setExternalControlSetpoint(float roll, float pitch, float yaw, float thrust, quint16 buttons, int joystickMode);
310 311

    /** @brief Set the values for the 6dof manual control of the vehicle */
dogmaphobic's avatar
dogmaphobic committed
312
#ifndef __mobile__
313
    void setManual6DOFControlCommands(double x, double y, double z, double roll, double pitch, double yaw);
dogmaphobic's avatar
dogmaphobic committed
314
#endif
315 316

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

319 320
    void startCalibration(StartCalibrationType calType);
    void stopCalibration(void);
321

322 323 324
    void startBusConfig(StartBusConfigType calType);
    void stopBusConfig(void);

325
    /** @brief Send command to map a RC channel to a parameter */
326
    void sendMapRCToParam(QString param_id, float scale, float value0, quint8 param_rc_channel_index, float valueMin, float valueMax);
327 328 329

    /** @brief Send command to disable all bindings/maps between RC and parameters */
    void unsetRCToParameterMap();
330 331 332 333 334
signals:
    void imageStarted(quint64 timestamp);
    /** @brief A new camera image has arrived */
    void imageReady(UASInterface* uas);
    /** @brief HIL controls have changed */
335
    void hilControlsChanged(quint64 time, float rollAilerons, float pitchElevator, float yawRudder, float throttle, quint8 systemMode, quint8 navMode);
336

337 338 339
    void rollChanged(double val,QString name);
    void pitchChanged(double val,QString name);
    void yawChanged(double val,QString name);
Don Gagne's avatar
Don Gagne committed
340

341 342 343 344 345 346 347
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);
348

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

Gus Grubba's avatar
Gus Grubba committed
351 352 353
    QMap<int, int>componentID;
    QMap<int, bool>componentMulti;

354 355
    bool connectionLost; ///< Flag indicates a timed out connection
    quint64 connectionLossTime; ///< Time the connection was interrupted
Ricardo de Almeida Gonzaga's avatar
Ricardo de Almeida Gonzaga committed
356
    quint64 lastVoltageWarning; ///< Time at which the last voltage warning occurred
357 358
    quint64 lastNonNullTime;    ///< The last timestamp from the MAV that was not null
    unsigned int onboardTimeOffsetInvalidCount;     ///< Count when the offboard time offset estimation seemed wrong
Don Gagne's avatar
Don Gagne committed
359
    bool hilEnabled;
360
    bool sensorHil;             ///< True if sensor HIL is enabled
361
    quint64 lastSendTimeGPS;     ///< Last HIL GPS message sent
362 363
    quint64 lastSendTimeSensors; ///< Last HIL Sensors message sent
    quint64 lastSendTimeOpticalFlow; ///< Last HIL Optical Flow message sent
364

365 366
private:
    void _say(const QString& text, int severity = 6);
367

368
private:
369 370
    Vehicle*                _vehicle;
    FirmwarePluginManager*  _firmwarePluginManager;
371 372 373 374
};


#endif // _UAS_H_