UAS.h 13.5 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 48 49 50

/**
 * @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:
51
    UAS(MAVLinkProtocol* protocol, int id = 0);
pixhawk's avatar
pixhawk committed
52 53
    ~UAS();

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

84 85 86 87 88 89
    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; }
lm's avatar
lm committed
90

91 92 93
    double getRoll() const { return roll; }
    double getPitch() const { return pitch; }
    double getYaw() const { return yaw; }
94
    bool getSelected() const;
lm's avatar
lm committed
95

pixhawk's avatar
pixhawk committed
96
friend class UASWaypointManager;
97

INIDETAM's avatar
INIDETAM committed
98
protected: //COMMENTS FOR TEST UNIT
99
    int uasId;                    ///< Unique system ID
100
    unsigned char type;           ///< UAS type (from type enum)
pixhawk's avatar
pixhawk committed
101 102 103
    quint64 startTime;            ///< The time the UAS was switched on
    CommStatus commStatus;        ///< Communication status
    QString name;                 ///< Human-friendly name of the vehicle, e.g. bravo
104
    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
105
    QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
106
    QList<int> unknownPackets;    ///< Packet IDs which are unknown and have been received
107
    MAVLinkProtocol* mavlink;     ///< Reference to the MAVLink instance
pixhawk's avatar
pixhawk committed
108 109
    BatteryType batteryType;      ///< The battery type
    int cells;                    ///< Number of cells
pixhawk's avatar
pixhawk committed
110

111 112
    UASWaypointManager waypointManager;

pixhawk's avatar
pixhawk committed
113 114 115 116 117 118
    QList<double> actuatorValues;
    QList<QString> actuatorNames;

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

pixhawk's avatar
pixhawk committed
119 120
    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
121 122

    // Battery stats
123 124 125
    float fullVoltage;          ///< Voltage of the fully charged battery (100%)
    float emptyVoltage;         ///< Voltage of the empty battery (0%)
    float startVoltage;         ///< Voltage at system start
126
    float warnVoltage;          ///< Voltage where QGC will start to warn about low battery
pixhawk's avatar
pixhawk committed
127 128 129
    double currentVoltage;      ///< Voltage currently measured
    float lpVoltage;            ///< Low-pass filtered voltage
    int timeRemaining;          ///< Remaining time calculated based on previous and current
lm's avatar
lm committed
130
    unsigned int mode;          ///< The current mode of the MAV
pixhawk's avatar
pixhawk committed
131
    int status;                 ///< The current status of the MAV
pixhawk's avatar
pixhawk committed
132 133
    quint64 onboardTimeOffset;

pixhawk's avatar
pixhawk committed
134 135 136 137 138 139 140 141 142
    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
143 144
    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
145
    bool lowBattAlarm;          ///< Switch if battery is low
146
    bool positionLock;          ///< Status if position information is available or not
lm's avatar
lm committed
147 148 149
    double localX;
    double localY;
    double localZ;
150 151 152
    double latitude;
    double longitude;
    double altitude;
153 154 155
    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
156 157 158
    double roll;
    double pitch;
    double yaw;
159
    quint64 lastHeartbeat;      ///< Time of the last heartbeat message
160
    QTimer* statusTimeout;      ///< Timer for various status timeouts
161 162
    QMap<int, QMap<QString, float>* > parameters; ///< All parameters
    bool paramsOnceRequested;   ///< If the parameter list has been read at least once
163
    int airframe;               ///< The airframe type
164
public:
pixhawk's avatar
pixhawk committed
165 166 167 168 169 170 171 172 173 174 175
    /** @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 */
    double 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();

176
    UASWaypointManager* getWaypointManager() { return &waypointManager; }
177
    int getSystemType();
178
    int getAutopilotType() {return autopilot;}
179

pixhawk's avatar
pixhawk committed
180
public slots:
181
    /** @brief Set the autopilot type */
182
    void setAutopilotType(int apType) { autopilot = apType; emit systemSpecsChanged(uasId); }
183
    /** @brief Set the type of airframe */
184
    void setSystemType(int systemType);
185 186
    /** @brief Set the specific airframe type */
    void setAirframe(int airframe) { this->airframe = airframe; emit systemSpecsChanged(uasId); }
187 188 189
    /** @brief Set a new name **/
    void setUASName(const QString& name);
    /** @brief Executes an action **/
190
    void setAction(MAV_ACTION action);
191 192 193 194
    /** @brief Set the current battery type and voltages */
    void setBatterySpecs(const QString& specs);
    /** @brief Get the current battery type and specs */
    QString getBatterySpecs();
195

pixhawk's avatar
pixhawk committed
196 197
    /** @brief Launches the system **/
    void launch();
lm's avatar
lm committed
198
    /** @brief Write this waypoint to the list of waypoints */
199
    //void setWaypoint(Waypoint* wp); FIXME tbd
lm's avatar
lm committed
200
    /** @brief Set currently active waypoint */
201
    //void setWaypointActive(int id); FIXME tbd
pixhawk's avatar
pixhawk committed
202 203 204 205 206 207 208 209 210 211 212 213 214
    /** @brief Order the robot to return home / to land on the runway **/
    void home();
    void halt();
    void go();
    /** @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();

215 216 217
    /** @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
218 219 220
    void startLowBattAlarm();
    void stopLowBattAlarm();

221 222
    //void requestWaypoints();  FIXME tbd
    //void clearWaypointList();   FIXME tbd
223

pixhawk's avatar
pixhawk committed
224 225 226 227 228 229 230 231 232 233
    /** @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
234
    /** @brief Add a link associated with this robot */
pixhawk's avatar
pixhawk committed
235
    void addLink(LinkInterface* link);
236 237
    /** @brief Remove a link associated with this robot */
    void removeLink(QObject* object);
pixhawk's avatar
pixhawk committed
238 239

    /** @brief Receive a message from one of the communication links. */
240
    virtual void receiveMessage(LinkInterface* link, mavlink_message_t message);
pixhawk's avatar
pixhawk committed
241 242 243 244 245 246

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

247 248 249
    /** @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
250 251 252 253
    /** @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
254
    void setMode(int mode);
pixhawk's avatar
pixhawk committed
255

256 257 258
    /** @brief Request all parameters */
    void requestParameters();

259
    /** @brief Set a system parameter */
lm's avatar
lm committed
260
    void setParameter(const int component, const QString& id, const float value);
261 262

    /** @brief Write parameters to permanent storage */
263 264 265
    void writeParametersToStorage();
    /** @brief Read parameters from permanent storage */
    void readParametersFromStorage();
266

267 268 269 270 271 272
    /** @brief Get the names of all parameters */
    QList<QString> getParameterNames(int component);

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

273 274 275 276 277 278 279 280 281 282
    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);
lm's avatar
lm committed
283

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

287 288
    /** @brief Set world frame origin at current GPS position */
    void setLocalOriginAtCurrentGPSPosition();
pixhawk's avatar
pixhawk committed
289 290
    /** @brief Set local position setpoint */
    void setLocalPositionSetpoint(float x, float y, float z, float yaw);
pixhawk's avatar
pixhawk committed
291 292 293 294 295 296 297
    /** @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
298

lm's avatar
lm committed
299 300 301 302
    void startDataRecording();
    void pauseDataRecording();
    void stopDataRecording();

pixhawk's avatar
pixhawk committed
303 304 305 306 307 308 309 310 311 312 313 314 315
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);
316
    void imageStarted(quint64 timestamp);
317 318 319 320

    protected:
    /** @brief Get the UNIX timestamp in microseconds */
    quint64 getUnixTime(quint64 time);
321 322

protected slots:
323 324 325 326
    /** @brief Write settings to disk */
    void writeSettings();
    /** @brief Read settings from disk */
    void readSettings();
327 328 329 330

    // MESSAGE RECEPTION
    /** @brief Receive a named value message */
    void receiveMessageNamedValue(const mavlink_message_t& message);
pixhawk's avatar
pixhawk committed
331 332 333 334
};


#endif // _UAS_H_