UAS.h 9.81 KB
Newer Older
pixhawk's avatar
pixhawk committed
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
/*=====================================================================

PIXHAWK Micro Air Vehicle Flying Robotics Toolkit

(c) 2009, 2010 PIXHAWK PROJECT  <http://pixhawk.ethz.ch>

This file is part of the PIXHAWK project

    PIXHAWK 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.

    PIXHAWK 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 PIXHAWK. 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 "MG.h"
37
#include <MAVLinkProtocol.h>
pixhawk's avatar
pixhawk committed
38 39 40 41 42 43 44 45 46 47 48 49 50
#include <mavlink.h>

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

pixhawk's avatar
pixhawk committed
82
friend class UASWaypointManager;
pixhawk's avatar
pixhawk committed
83
protected:
84 85
    int uasId;                    ///< Unique system ID
    int type;                     ///< UAS type (from type enum)
pixhawk's avatar
pixhawk committed
86 87 88
    quint64 startTime;            ///< The time the UAS was switched on
    CommStatus commStatus;        ///< Communication status
    QString name;                 ///< Human-friendly name of the vehicle, e.g. bravo
pixhawk's avatar
pixhawk committed
89
    QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
90
    QList<int> unknownPackets;    ///< Packet IDs which are unknown and have been received
91
    MAVLinkProtocol* mavlink;     ///< Reference to the MAVLink instance
pixhawk's avatar
pixhawk committed
92 93
    BatteryType batteryType;      ///< The battery type
    int cells;                    ///< Number of cells
pixhawk's avatar
pixhawk committed
94

95 96
    UASWaypointManager waypointManager;

pixhawk's avatar
pixhawk committed
97 98 99 100 101 102
    QList<double> actuatorValues;
    QList<QString> actuatorNames;

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

pixhawk's avatar
pixhawk committed
103 104
    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
105 106

    // Battery stats
pixhawk's avatar
pixhawk committed
107 108 109 110 111 112
    double fullVoltage;         ///< Voltage of the fully charged battery (100%)
    double emptyVoltage;        ///< Voltage of the empty battery (0%)
    double startVoltage;        ///< Voltage at system start
    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
113
    unsigned int mode;          ///< The current mode of the MAV
pixhawk's avatar
pixhawk committed
114
    int status;                 ///< The current status of the MAV
pixhawk's avatar
pixhawk committed
115 116
    quint64 onboardTimeOffset;

pixhawk's avatar
pixhawk committed
117 118 119 120 121 122 123 124 125
    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
126 127
    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
128
    bool lowBattAlarm;          ///< Switch if battery is low
129 130
    bool positionLock;          ///< Status if position information is available or not
    QTimer* statusTimeout;      ///< Timer for various status timeouts
pixhawk's avatar
pixhawk committed
131

pixhawk's avatar
pixhawk committed
132 133 134 135 136 137 138 139 140 141 142
    /** @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();

143 144 145
public:
    UASWaypointManager &getWaypointManager(void) { return waypointManager; }

pixhawk's avatar
pixhawk committed
146 147 148
public slots:
    /** @brief Launches the system **/
    void launch();
lm's avatar
lm committed
149
    /** @brief Write this waypoint to the list of waypoints */
150
    //void setWaypoint(Waypoint* wp); FIXME tbd
lm's avatar
lm committed
151
    /** @brief Set currently active waypoint */
152
    //void setWaypointActive(int id); FIXME tbd
pixhawk's avatar
pixhawk committed
153 154 155 156 157 158 159 160 161 162 163 164 165
    /** @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();

lm's avatar
lm committed
166 167 168
    void startLowBattAlarm();
    void stopLowBattAlarm();

169 170
    //void requestWaypoints();  FIXME tbd
    //void clearWaypointList();   FIXME tbd
171
    void requestParameters();
pixhawk's avatar
pixhawk committed
172 173 174 175 176 177 178 179 180 181
    /** @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
182
    /** @brief Add a link associated with this robot */
pixhawk's avatar
pixhawk committed
183 184 185 186 187 188 189 190 191 192 193 194 195 196
    void addLink(LinkInterface* link);

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

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

    /** @brief Set current mode of operation, e.g. auto or manual */
pixhawk's avatar
pixhawk committed
197
    void setMode(int mode);
pixhawk's avatar
pixhawk committed
198

199 200 201 202
    /** @brief Set a system parameter */
    void setParameter(int component, QString id, float value);

    /** @brief Write parameters to permanent storage */
203 204 205
    void writeParametersToStorage();
    /** @brief Read parameters from permanent storage */
    void readParametersFromStorage();
206

lm's avatar
lm committed
207 208 209 210 211 212
    void enableAllDataTransmission(bool enabled);
    void enableRawSensorDataTransmission(bool enabled);
    void enableExtendedSystemStatusTransmission(bool enabled);
    void enableRCChannelDataTransmission(bool enabled);
    void enableRawControllerDataTransmission(bool enabled);
    void enableRawSensorFusionTransmission(bool enabled);
pixhawk's avatar
pixhawk committed
213 214 215 216
    void enablePositionTransmission(bool enabled);
    void enableExtra1Transmission(bool enabled);
    void enableExtra2Transmission(bool enabled);
    void enableExtra3Transmission(bool enabled);
lm's avatar
lm committed
217

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

pixhawk's avatar
pixhawk committed
221 222 223
    /** @brief Set local position setpoint */
    void setLocalPositionSetpoint(float x, float y, float z, float yaw);

pixhawk's avatar
pixhawk committed
224 225 226 227 228 229 230 231 232 233 234 235 236
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);
237 238 239 240

    protected:
    /** @brief Get the UNIX timestamp in microseconds */
    quint64 getUnixTime(quint64 time);
pixhawk's avatar
pixhawk committed
241 242 243 244
};


#endif // _UAS_H_