WatchdogControl.h 5.9 KB
Newer Older
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
/*=====================================================================

QGroundControl Open Source Ground Control Station

(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>

This file is part of the QGROUNDCONTROL project

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

    QGROUNDCONTROL 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 QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.

======================================================================*/

/**
 * @file
 *   @brief Definition of class WatchdogControl
 *   @author Lorenz Meier <mavteam@student.ethz.ch>
 *
 */

31 32 33
#ifndef WATCHDOGCONTROL_H
#define WATCHDOGCONTROL_H

34 35
#include <inttypes.h>

36 37
#include <QWidget>
#include <QTimer>
38
#include <QVBoxLayout>
39 40 41 42 43

#include <map>
#include <string>
#include <sstream>

44 45
#include "WatchdogView.h"

46 47
#include "UASInterface.h"

48 49 50
namespace Ui
{
class WatchdogControl;
51 52
}

53 54 55
/**
 * @brief Overall widget for controlling all watchdogs of all connected MAVs
 */
56 57
class WatchdogControl : public QWidget
{
58 59 60 61 62
    Q_OBJECT
public:


    ///! Command codes, used to send and receive commands over lcm
63 64
    struct Command {
        enum Enum {
65 66 67 68 69 70 71 72
            Start         = 0,
            Restart       = 1,
            Stop          = 2,
            Mute          = 3,
            Unmute        = 4,

            RequestInfo   = 254,
            RequestStatus = 255
73
        };
74 75 76
    };

    ///! This struct represents a process on the watchdog. Used to store all values.
77
    struct ProcessInfo {
78
        ///! Process state - each process is in exactly one of those states (except unknown, that's just to initialize it)
79 80
        struct State {
            enum Enum {
81 82 83 84 85
                Unknown       = 0,
                Running       = 1,
                Stopped       = 2,
                Stopped_OK    = 3,
                Stopped_ERROR = 4
86
            };
87 88 89 90 91 92 93 94 95 96 97 98 99 100 101
        };

        ///! Constructor - initialize the values
        ProcessInfo() : timeout_(0), state_(State::Unknown), muted_(false), crashes_(0), pid_(-1) {}

        std::string name_;      ///< The name of the process
        std::string arguments_; ///< The arguments (argv of the process)

        int32_t timeout_;       ///< Heartbeat timeout value (in microseconds)

        State::Enum state_;     ///< The current state of the process
        bool muted_;            ///< True if the process is currently muted
        uint16_t crashes_;      ///< The number of crashes
        int32_t pid_;           ///< The PID of the process

pixhawk's avatar
pixhawk committed
102
        //quint64_t requestTimeout;
103 104
        //    Timer requestTimer_;    ///< Internal timer, used to repeat status and info requests after some time (in case of packet loss)
        //    Timer updateTimer_;     ///< Internal timer, used to measure the time since the last update (used only for graphics)
105 106 107
    };

    ///! This struct identifies a watchdog. It's a combination of system-ID and watchdog-ID. implements operator< to be used as key in a std::map
108
    struct WatchdogID {
109 110 111 112 113 114 115
        ///! Constructor - initialize the values
        WatchdogID(uint8_t system_id, uint16_t watchdog_id) : system_id_(system_id), watchdog_id_(watchdog_id) {}

        uint8_t system_id_;     ///< The system-ID
        uint16_t watchdog_id_;  ///< The watchdog-ID

        ///! Comparison operator which is used by std::map
116 117 118
        inline bool operator<(const WatchdogID& other) const {
            return (this->system_id_ != other.system_id_) ? (this->system_id_ < other.system_id_) : (this->watchdog_id_ < other.watchdog_id_);
        }
119 120 121 122

    };

    ///! This struct represents a watchdog
123
    struct WatchdogInfo {
124 125 126
        ProcessInfo& getProcess(uint16_t index);

        std::vector<ProcessInfo> processes_;    ///< A vector containing all processes running on this watchdog
pixhawk's avatar
pixhawk committed
127
        uint64_t timeout;
128 129 130
        QTimer* timeoutTimer_;                    ///< Internal timer, used to measure the time since the last heartbeat message
    };

lm's avatar
lm committed
131
    WatchdogControl(QWidget *parent = 0);
132 133 134 135 136 137 138 139 140 141
    ~WatchdogControl();

    static const uint16_t ALL         = (uint16_t)-1;   ///< A magic value for a process-ID which addresses "all processes"
    static const uint16_t ALL_RUNNING = (uint16_t)-2;   ///< A magic value for a process-ID which addresses "all running processes"
    static const uint16_t ALL_CRASHED = (uint16_t)-3;   ///< A magic value for a process-ID which addresses "all crashed processes"

public slots:
    void updateWatchdog(int systemId, int watchdogId, unsigned int processCount);
    void addProcess(int systemId, int watchdogId, int processId, QString name, QString arguments, int timeout);
    void updateProcess(int systemId, int watchdogId, int processId, int state, bool muted, int crashed, int pid);
lm's avatar
lm committed
142
    void setUAS(UASInterface* uas);
143

144 145 146
signals:
    void sendProcessCommand(int watchdogId, int processId, unsigned int command);

147 148 149
protected:
    void changeEvent(QEvent *e);

150
    UASInterface* mav;
151
    QVBoxLayout* listLayout;
pixhawk's avatar
pixhawk committed
152
    uint64_t updateInterval;
153

154 155 156 157 158 159 160 161
private:
    Ui::WatchdogControl *ui;

    void sendCommand(const WatchdogID& w_id, uint16_t p_id, Command::Enum command);

    WatchdogInfo& getWatchdog(uint8_t system_id, uint16_t watchdog_id);

    std::map<WatchdogID, WatchdogInfo> watchdogs_;          ///< A map containing all watchdogs which are currently active
162
    std::map<WatchdogID, WatchdogView> views;
163 164 165 166 167 168 169
    QTimer updateTimer_;
};

#endif // WATCHDOGCONTROL_H

///! Convert a value to std::string
template <class T>
170
std::string convertToString(T value)
171
{
172 173 174
    std::ostringstream oss;
    oss << value;
    return oss.str();
175
}