Commit a994cdc1 authored by pixhawk's avatar pixhawk

Added complete Watchdog comm methods, testing code

parent 62b184bb
...@@ -62,7 +62,8 @@ INCLUDEPATH += src \ ...@@ -62,7 +62,8 @@ INCLUDEPATH += src \
src/input \ src/input \
src/lib/qmapcontrol \ src/lib/qmapcontrol \
src/ui/mavlink \ src/ui/mavlink \
src/ui/param src/ui/param \
src/ui/watchdog
HEADERS += src/MG.h \ HEADERS += src/MG.h \
src/Core.h \ src/Core.h \
src/uas/UASInterface.h \ src/uas/UASInterface.h \
......
...@@ -98,6 +98,7 @@ MainWindow::MainWindow(QWidget *parent) : QMainWindow(parent), ...@@ -98,6 +98,7 @@ MainWindow::MainWindow(QWidget *parent) : QMainWindow(parent),
centerStack->addWidget(protocol); centerStack->addWidget(protocol);
parameters = new ParameterInterface(this); parameters = new ParameterInterface(this);
parameters->setVisible(false); parameters->setVisible(false);
watchdogControl = new WatchdogControl(this);
QStringList* acceptList = new QStringList(); QStringList* acceptList = new QStringList();
acceptList->append("roll IMU"); acceptList->append("roll IMU");
......
...@@ -60,6 +60,7 @@ This file is part of the PIXHAWK project ...@@ -60,6 +60,7 @@ This file is part of the PIXHAWK project
#include "ParameterInterface.h" #include "ParameterInterface.h"
#include "XMLCommProtocolWidget.h" #include "XMLCommProtocolWidget.h"
#include "HDDisplay.h" #include "HDDisplay.h"
#include "WatchdogControl.h"
#include "LogCompressor.h" #include "LogCompressor.h"
...@@ -146,6 +147,7 @@ protected: ...@@ -146,6 +147,7 @@ protected:
XMLCommProtocolWidget* protocol; XMLCommProtocolWidget* protocol;
HDDisplay* headDown1; HDDisplay* headDown1;
HDDisplay* headDown2; HDDisplay* headDown2;
WatchdogControl* watchdogControl;
// Popup widgets // Popup widgets
JoystickWidget* joystickWidget; JoystickWidget* joystickWidget;
......
...@@ -2,6 +2,8 @@ ...@@ -2,6 +2,8 @@
#include "ui_WatchdogControl.h" #include "ui_WatchdogControl.h"
#include "PxQuadMAV.h" #include "PxQuadMAV.h"
#include "UASManager.h"
#include <QDebug> #include <QDebug>
WatchdogControl::WatchdogControl(QWidget *parent) : WatchdogControl::WatchdogControl(QWidget *parent) :
...@@ -10,6 +12,7 @@ WatchdogControl::WatchdogControl(QWidget *parent) : ...@@ -10,6 +12,7 @@ WatchdogControl::WatchdogControl(QWidget *parent) :
ui(new Ui::WatchdogControl) ui(new Ui::WatchdogControl)
{ {
ui->setupUi(this); ui->setupUi(this);
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
} }
WatchdogControl::~WatchdogControl() WatchdogControl::~WatchdogControl()
...@@ -24,6 +27,8 @@ void WatchdogControl::setUAS(UASInterface* uas) ...@@ -24,6 +27,8 @@ void WatchdogControl::setUAS(UASInterface* uas)
if (qmav) if (qmav)
{ {
connect(qmav, SIGNAL(processReceived(int,int,int,QString,QString,int)), this, SLOT(addProcess(int,int,int,QString,QString,int))); connect(qmav, SIGNAL(processReceived(int,int,int,QString,QString,int)), this, SLOT(addProcess(int,int,int,QString,QString,int)));
connect(qmav, SIGNAL(watchdogReceived(int,int,int)), this, SLOT(updateWatchdog(int,int,uint)));
connect(qmav, SIGNAL(processChanged(int,int,int,int,bool,int,int)), this, SLOT(updateProcess(int,int,int,int,bool,int,int)));
} }
} }
...@@ -38,6 +43,7 @@ void WatchdogControl::updateWatchdog(int systemId, int watchdogId, unsigned int ...@@ -38,6 +43,7 @@ void WatchdogControl::updateWatchdog(int systemId, int watchdogId, unsigned int
// start the timeout timer // start the timeout timer
//watchdog.timeoutTimer_.reset(); //watchdog.timeoutTimer_.reset();
qDebug() << "WATCHDOG RECEIVED";
//qDebug() << "<-- received mavlink_watchdog_heartbeat_t " << msg->sysid << " / " << payload.watchdog_id << " / " << payload.process_count << std::endl; //qDebug() << "<-- received mavlink_watchdog_heartbeat_t " << msg->sysid << " / " << payload.watchdog_id << " / " << payload.process_count << std::endl;
} }
...@@ -51,6 +57,7 @@ void WatchdogControl::addProcess(int systemId, int watchdogId, int processId, QS ...@@ -51,6 +57,7 @@ void WatchdogControl::addProcess(int systemId, int watchdogId, int processId, QS
process.name_ = name.toStdString(); process.name_ = name.toStdString();
process.arguments_ = arguments.toStdString(); process.arguments_ = arguments.toStdString();
process.timeout_ = timeout; process.timeout_ = timeout;
qDebug() << "PROCESS RECEIVED";
//qDebug() << "<-- received mavlink_watchdog_process_info_t " << msg->sysid << " / " << (const char*)payload.name << " / " << (const char*)payload.arguments << " / " << payload.timeout << std::endl; //qDebug() << "<-- received mavlink_watchdog_process_info_t " << msg->sysid << " / " << (const char*)payload.name << " / " << (const char*)payload.arguments << " / " << payload.timeout << std::endl;
} }
...@@ -67,6 +74,7 @@ void WatchdogControl::updateProcess(int systemId, int watchdogId, int processId, ...@@ -67,6 +74,7 @@ void WatchdogControl::updateProcess(int systemId, int watchdogId, int processId,
process.crashes_ = crashes; process.crashes_ = crashes;
process.pid_ = pid; process.pid_ = pid;
qDebug() << "PROCESS UPDATED";
//process.updateTimer_.reset(); //process.updateTimer_.reset();
//qDebug() << "<-- received mavlink_watchdog_process_status_t " << msg->sysid << " / " << payload.state << " / " << payload.muted << " / " << payload.crashes << " / " << payload.pid << std::endl; //qDebug() << "<-- received mavlink_watchdog_process_status_t " << msg->sysid << " / " << payload.state << " / " << payload.muted << " / " << payload.crashes << " / " << payload.pid << std::endl;
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment