UAS.h 8.04 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 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68
    ~UAS();

    enum BatteryType {
        NICD = 0,
        NIMH = 1,
        LIION = 2,
        LIPOLY = 3,
        LIFE = 4,
        AGZN = 5
           }; ///< The type of battery used

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

    /* MANAGEMENT */

    /** @brief The name of the robot */
pixhawk's avatar
pixhawk committed
69
    QString getUASName(void);
pixhawk's avatar
pixhawk committed
70 71 72 73 74 75 76
    /** @brief Get the unique system id */
    int getUASID();
    /** @brief The time interval the robot is switched on */
    quint64 getUptime();
    /** @brief Get the status flag for the communication */
    int getCommunicationStatus();
    /** @brief Add one measurement and get low-passed voltage */
pixhawk's avatar
pixhawk committed
77
    const float filterVoltage(float value);
pixhawk's avatar
pixhawk committed
78 79 80 81 82
    /** @brief Get the links associated with this robot */
    QList<LinkInterface*>* getLinks();

protected:
    int type;
pixhawk's avatar
pixhawk committed
83 84 85 86
    quint64 startTime;            ///< The time the UAS was switched on
    CommStatus commStatus;        ///< Communication status
    int uasId;                    ///< Unique system ID
    QString name;                 ///< Human-friendly name of the vehicle, e.g. bravo
pixhawk's avatar
pixhawk committed
87
    QList<LinkInterface*>* links; ///< List of links this UAS can be reached by
88
    MAVLinkProtocol* mavlink;     ///< Reference to the MAVLink instance
pixhawk's avatar
pixhawk committed
89 90
    BatteryType batteryType;      ///< The battery type
    int cells;                    ///< Number of cells
pixhawk's avatar
pixhawk committed
91 92 93 94 95 96

    QList<double> actuatorValues;
    QList<QString> actuatorNames;

    QList<double> motorValues;
    QList<QString> motorNames;
lm's avatar
lm committed
97
    QList<int> unknownPackets;  ///< Packet IDs which are unknown and have been received
pixhawk's avatar
pixhawk committed
98

pixhawk's avatar
pixhawk committed
99 100
    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
101 102

    // Battery stats
pixhawk's avatar
pixhawk committed
103 104 105 106 107 108 109 110
    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
    int mode;                   ///< The current mode of the MAV
    int status;                 ///< The current status of the MAV
pixhawk's avatar
pixhawk committed
111 112
    quint64 onboardTimeOffset;

pixhawk's avatar
pixhawk committed
113 114 115 116 117 118 119 120 121
    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
122 123
    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
pixhawk's avatar
pixhawk committed
124

pixhawk's avatar
pixhawk committed
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
    /** @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();

public slots:
    /** @brief Launches the system **/
    void launch();
    void setWaypoint(Waypoint* wp);
    void setWaypointActive(int id);
    /** @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();

    void requestWaypoints();
155
    void requestParameters();
pixhawk's avatar
pixhawk committed
156 157 158 159 160 161 162 163 164 165 166
    void clearWaypointList();
    /** @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
167
    /** @brief Add a link associated with this robot */
pixhawk's avatar
pixhawk committed
168 169 170 171 172 173 174 175 176 177 178 179 180 181
    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
182
    void setMode(int mode);
pixhawk's avatar
pixhawk committed
183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200

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);
};


#endif // _UAS_H_