WatchdogControl.cc 5.36 KB
Newer Older
1 2
#include "WatchdogControl.h"
#include "ui_WatchdogControl.h"
3
#include "PxQuadMAV.h"
4

5 6
#include "UASManager.h"

7 8
#include <QDebug>

lm's avatar
lm committed
9
WatchdogControl::WatchdogControl(QWidget *parent) :
10
        QWidget(parent),
11
        mav(NULL),
pixhawk's avatar
pixhawk committed
12
        updateInterval(2000000),
13 14 15
        ui(new Ui::WatchdogControl)
{
    ui->setupUi(this);
pixhawk's avatar
pixhawk committed
16 17

    // UI is initialized, setup layout
18
    listLayout = new QVBoxLayout(ui->mainWidget);
pixhawk's avatar
pixhawk committed
19 20 21
    listLayout->setSpacing(6);
    listLayout->setMargin(0);
    listLayout->setAlignment(Qt::AlignTop);
22
    ui->mainWidget->setLayout(listLayout);
pixhawk's avatar
pixhawk committed
23

24
    connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
25 26 27 28 29 30 31
}

WatchdogControl::~WatchdogControl()
{
    delete ui;
}

32 33
void WatchdogControl::setUAS(UASInterface* uas)
{
lm's avatar
lm committed
34
    PxQuadMAV* qmav = dynamic_cast<PxQuadMAV*>(uas);
35 36 37 38

    if (qmav)
    {
        connect(qmav, SIGNAL(processReceived(int,int,int,QString,QString,int)), this, SLOT(addProcess(int,int,int,QString,QString,int)));
pixhawk's avatar
pixhawk committed
39
        connect(qmav, SIGNAL(watchdogReceived(int,int,uint)), this, SLOT(updateWatchdog(int,int,uint)));
40
        connect(qmav, SIGNAL(processChanged(int,int,int,int,bool,int,int)), this, SLOT(updateProcess(int,int,int,int,bool,int,int)));
41 42 43
    }
}

44 45 46
void WatchdogControl::updateWatchdog(int systemId, int watchdogId, unsigned int processCount)
{
    // request the watchdog with the given ID
pixhawk's avatar
pixhawk committed
47
    // Get the watchdog and request the info for it
48 49 50 51
    WatchdogInfo& watchdog = this->getWatchdog(systemId, watchdogId);

    // if the proces count doesn't match, the watchdog is either new or has changed - create a new vector with new (and empty) ProcessInfo structs.
    if (watchdog.processes_.size() != processCount)
pixhawk's avatar
pixhawk committed
52
    {
53
        watchdog.processes_ = std::vector<ProcessInfo>(processCount);
pixhawk's avatar
pixhawk committed
54 55 56
        // Create new UI widget
        //WatchdogView* view = new Watch
    }
57 58 59

    // start the timeout timer
    //watchdog.timeoutTimer_.reset();
pixhawk's avatar
pixhawk committed
60

61
    qDebug() << "WATCHDOG RECEIVED";
62 63 64 65 66 67 68 69 70 71 72 73 74
    //qDebug() << "<-- received mavlink_watchdog_heartbeat_t " << msg->sysid << " / " << payload.watchdog_id << " / " << payload.process_count << std::endl;
}

void WatchdogControl::addProcess(int systemId, int watchdogId, int processId, QString name, QString arguments, int timeout)
{
    // request the watchdog and the process with the given IDs
    WatchdogInfo& watchdog = this->getWatchdog(systemId, watchdogId);
    ProcessInfo& process = watchdog.getProcess(processId);

    // store the process information in the ProcessInfo struct
    process.name_ = name.toStdString();
    process.arguments_ = arguments.toStdString();
    process.timeout_ = timeout;
75
    qDebug() << "PROCESS RECEIVED";
76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91
    //qDebug() << "<-- received mavlink_watchdog_process_info_t " << msg->sysid << " / " << (const char*)payload.name << " / " << (const char*)payload.arguments << " / " << payload.timeout << std::endl;
}


void WatchdogControl::updateProcess(int systemId, int watchdogId, int processId, int state, bool muted, int crashes, int pid)
{
    // request the watchdog and the process with the given IDs
    WatchdogInfo& watchdog = this->getWatchdog(systemId, watchdogId);
    ProcessInfo& process = watchdog.getProcess(processId);

    // store the status information in the ProcessInfo struct
    process.state_ = static_cast<ProcessInfo::State::Enum>(state);
    process.muted_ = muted;
    process.crashes_ = crashes;
    process.pid_ = pid;

92
    qDebug() << "PROCESS UPDATED";
93 94 95 96 97 98 99 100 101 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
    //process.updateTimer_.reset();
    //qDebug() << "<-- received mavlink_watchdog_process_status_t " << msg->sysid << " / " << payload.state << " / " << payload.muted << " / " << payload.crashes << " / " << payload.pid << std::endl;
}

/**
    @brief Returns a WatchdogInfo struct that belongs to the watchdog with the given system-ID and watchdog-ID
*/
WatchdogControl::WatchdogInfo& WatchdogControl::getWatchdog(uint8_t systemId, uint16_t watchdogId)
{
    WatchdogID id(systemId, watchdogId);

    std::map<WatchdogID, WatchdogInfo>::iterator it = this->watchdogs_.find(id);
    if (it != this->watchdogs_.end())
    {
        // the WatchdogInfo struct already exists in the map, return it
        return it->second;
    }
    else
    {
        // the WatchdogInfo struct doesn't exist - request info and status for all processes and create the struct
        this->sendCommand(id, WatchdogControl::ALL, Command::RequestInfo);
        this->sendCommand(id, WatchdogControl::ALL, Command::RequestStatus);
        return this->watchdogs_[id];
    }
}

/**
    @brief Returns a ProcessInfo struct that belongs to the process with the given ID.
*/
WatchdogControl::ProcessInfo& WatchdogControl::WatchdogInfo::getProcess(uint16_t index)
{
    // if the index is out of bounds, resize the vector
    if (index >= this->processes_.size())
        this->processes_.resize(index + 1);

    return this->processes_[index];
}

/**
    @brief Sends a watchdog command to a process on a given watchdog.
    @param w_id The WatchdogID struct (containing system-ID and watchdog-ID) that identifies the watchdog
    @param p_id The process-ID
    @param command The command-ID
*/
void WatchdogControl::sendCommand(const WatchdogID& w_id, uint16_t p_id, Command::Enum command)
{
139
    emit sendProcessCommand(w_id.watchdog_id_, p_id, command);
140 141 142 143 144 145 146 147 148 149 150 151 152
}

void WatchdogControl::changeEvent(QEvent *e)
{
    QWidget::changeEvent(e);
    switch (e->type()) {
    case QEvent::LanguageChange:
        ui->retranslateUi(this);
        break;
    default:
        break;
    }
}