From 3bfeac6717cc0dcf9fb690302bc40fc0d457ea19 Mon Sep 17 00:00:00 2001 From: mantelt Date: Mon, 14 Sep 2015 20:35:32 +0200 Subject: [PATCH 1/5] changes to make qgc compile under linux with newest mavlink messages --- libs/mavlink/include/mavlink/v1.0 | 2 +- src/comm/MAVLinkSimulationLink.cc | 2 +- src/comm/MAVLinkSimulationMAV.cc | 2 +- src/uas/UAS.h | 6 +++--- src/uas/UASWaypointManager.cc | 4 ++-- src/ui/energybudget.cpp | 14 +++++++++----- 6 files changed, 17 insertions(+), 13 deletions(-) diff --git a/libs/mavlink/include/mavlink/v1.0 b/libs/mavlink/include/mavlink/v1.0 index 5a8a442b89b..8dfbf23e4be 160000 --- a/libs/mavlink/include/mavlink/v1.0 +++ b/libs/mavlink/include/mavlink/v1.0 @@ -1 +1 @@ -Subproject commit 5a8a442b89b235d90285b34bfdbb7efc0b9e3df6 +Subproject commit 8dfbf23e4be2747b81a5e78595978c17ecd15891 diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 0403823767f..94f85501b3a 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -507,7 +507,7 @@ void MAVLinkSimulationLink::mainloop() typeCounter++; // Pack message and get size of encoded byte string - mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_AUTOPILOT_PIXHAWK, system.base_mode, system.custom_mode, system.system_status); + mavlink_msg_heartbeat_pack(systemId, componentId, &msg, mavType, MAV_AUTOPILOT_GENERIC, system.base_mode, system.custom_mode, system.system_status); // Allocate buffer with packet data bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); //qDebug() << "CRC:" << msg.ck_a << msg.ck_b; diff --git a/src/comm/MAVLinkSimulationMAV.cc b/src/comm/MAVLinkSimulationMAV.cc index af12867dd26..310e01f681e 100644 --- a/src/comm/MAVLinkSimulationMAV.cc +++ b/src/comm/MAVLinkSimulationMAV.cc @@ -72,7 +72,7 @@ void MAVLinkSimulationMAV::mainloop() // 1 Hz execution if (timer1Hz <= 0) { mavlink_message_t msg; - mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_PIXHAWK, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE); + mavlink_msg_heartbeat_pack(systemid, MAV_COMP_ID_IMU, &msg, MAV_TYPE_FIXED_WING, MAV_AUTOPILOT_GENERIC, MAV_MODE_GUIDED_ARMED, 0, MAV_STATE_ACTIVE); link->sendMAVLinkMessage(&msg); planner.handleMessage(msg); diff --git a/src/uas/UAS.h b/src/uas/UAS.h index 519f1264e89..7ace87b0357 100644 --- a/src/uas/UAS.h +++ b/src/uas/UAS.h @@ -615,9 +615,9 @@ class UAS : public UASInterface case MAV_AUTOPILOT_GENERIC: return "GENERIC"; break; - case MAV_AUTOPILOT_PIXHAWK: - return "PIXHAWK"; - break; +// case MAV_AUTOPILOT_PIXHAWK: +// return "PIXHAWK"; +// break; case MAV_AUTOPILOT_SLUGS: return "SLUGS"; break; diff --git a/src/uas/UASWaypointManager.cc b/src/uas/UASWaypointManager.cc index fdc91411884..11b64aea14c 100644 --- a/src/uas/UASWaypointManager.cc +++ b/src/uas/UASWaypointManager.cc @@ -1178,7 +1178,7 @@ void UASWaypointManager::_updateWPonTimer() { while (current_state != WP_IDLE) { - Sleep(100); + sleep(100); } readWaypoints(true); -} \ No newline at end of file +} diff --git a/src/ui/energybudget.cpp b/src/ui/energybudget.cpp index 528029e944d..f6b26368a90 100644 --- a/src/ui/energybudget.cpp +++ b/src/ui/energybudget.cpp @@ -65,8 +65,8 @@ m_mpptHyst(new Hysteresisf(CELLPOWERHYSTMIN, CELLPOWERHYSTMAX, true)), m_MPPTUpdateReset(new QTimer(this)) { ui->setupUi(this); - ui->overviewGraphicsView->setHorizontalScrollBarPolicy(Qt::ScrollBarPolicy::ScrollBarAlwaysOff); - ui->overviewGraphicsView->setVerticalScrollBarPolicy(Qt::ScrollBarPolicy::ScrollBarAlwaysOff); + ui->overviewGraphicsView->setHorizontalScrollBarPolicy(Qt::ScrollBarAlwaysOff); + ui->overviewGraphicsView->setVerticalScrollBarPolicy(Qt::ScrollBarAlwaysOff); this->buildGraphicsImage(); ui->overviewGraphicsView->setScene(m_scene); ui->overviewGraphicsView->fitInView(m_scene->sceneRect(), Qt::KeepAspectRatio); @@ -99,9 +99,13 @@ void EnergyBudget::buildGraphicsImage() m_scene->setSceneRect(0.0, 0.0, 1000.0, 1000.0); qreal penWidth(40); // scale and place images - m_propPixmap->setScale(this->adjustImageScale(m_scene->sceneRect(), m_propPixmap->boundingRect())); - m_cellPixmap->setScale(this->adjustImageScale(m_scene->sceneRect(), m_cellPixmap->boundingRect())); - m_batPixmap->setScale(this->adjustImageScale(m_scene->sceneRect(), m_batPixmap->boundingRect())); + + QRectF temp=m_propPixmap->boundingRect(); + m_propPixmap->setScale(this->adjustImageScale(m_scene->sceneRect(), temp )); + temp=m_cellPixmap->boundingRect(); + m_cellPixmap->setScale(this->adjustImageScale(m_scene->sceneRect(), temp )); + temp=m_batPixmap->boundingRect(); + m_batPixmap->setScale(this->adjustImageScale(m_scene->sceneRect(), temp )); double maxheight(std::fmax(m_propPixmap->mapRectToScene(m_propPixmap->boundingRect()).height(), m_batPixmap->mapRectToScene(m_batPixmap->boundingRect()).height())); m_propPixmap->setOffset(0.0, m_propPixmap->mapRectFromScene(m_scene->sceneRect()).height() - m_propPixmap->mapRectFromScene(QRectF(0.0,0.0,1.0,maxheight)).height()/2.0 - m_propPixmap->boundingRect().height() / 2.0); m_batPixmap->setOffset(m_batPixmap->mapRectFromScene(m_scene->sceneRect()).width() - m_batPixmap->boundingRect().width(), m_batPixmap->mapRectFromScene(m_scene->sceneRect()).height() - m_batPixmap->mapRectFromScene(QRectF(0.0, 0.0, 1.0, maxheight)).height() / 2.0 - m_batPixmap->boundingRect().height() / 2.0); From 431db9de2132adcc302a44c9f44d84d3db3ab118 Mon Sep 17 00:00:00 2001 From: mantelt Date: Mon, 14 Sep 2015 20:35:51 +0200 Subject: [PATCH 2/5] started work on sensorpodstatus widget --- src/ui/sensorpodstatus.ui | 202 ++++++++++++++++++++++++++++++++++++++ 1 file changed, 202 insertions(+) create mode 100644 src/ui/sensorpodstatus.ui diff --git a/src/ui/sensorpodstatus.ui b/src/ui/sensorpodstatus.ui new file mode 100644 index 00000000000..8456818c4bc --- /dev/null +++ b/src/ui/sensorpodstatus.ui @@ -0,0 +1,202 @@ + + + EnergyBudget + + + + 0 + 0 + 268 + 340 + + + + Form + + + + + + QTabWidget::Triangular + + + 0 + + + + Overview + + + + + + ROS Topic Rates + + + + + + Topic 4 + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + Topic 1 + + + + + + + ??? + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + ??? + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + ??? + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + Topic 3 + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + ??? + + + + + + + Topic 2 + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + + + + General Information + + + + + + Number of recording nodes + + + + + + + ??? + + + Qt::AlignCenter + + + + + + + Free disk space + + + + + + + CPU Temperature + + + + + + + ??? + + + Qt::AlignCenter + + + + + + + ??? + + + Qt::AlignCenter + + + + + + + + + + + CMD + + + + + 70 + 20 + 111 + 31 + + + + Perform a power cycle of the whole pod + + + Power Cycle + + + + + + + + + + From a6c3a7bca81bf95bc154e845e245f6028764efab Mon Sep 17 00:00:00 2001 From: mantelt Date: Tue, 15 Sep 2015 14:23:22 +0200 Subject: [PATCH 3/5] First working version of Sensorpod Status Widget. --- qgroundcontrol.pro | 4 + src/uas/ASLUAV.cc | 21 ++++- src/uas/ASLUAV.h | 3 +- src/ui/MainWindow.cc | 9 +- src/ui/MainWindow.h | 1 + src/ui/sensorpodstatus.cpp | 102 +++++++++++++++++++++ src/ui/sensorpodstatus.h | 39 ++++++++ src/ui/sensorpodstatus.ui | 181 ++++++++++++++++++++++++++----------- 8 files changed, 304 insertions(+), 56 deletions(-) create mode 100644 src/ui/sensorpodstatus.cpp create mode 100644 src/ui/sensorpodstatus.h diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index ce2a7265799..7b0a991f3a5 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -153,6 +153,7 @@ MacBuild { LinuxBuild { DEFINES += __STDC_LIMIT_MACROS CONFIG += qesp_linux_udev + QMAKE_CXXFLAGS += -std=c++11 } WindowsBuild { @@ -353,6 +354,7 @@ FORMS += \ src/ui/QGCCommConfiguration.ui \ src/ui/QGCUDPLinkConfiguration.ui \ src/ui/energybudget.ui \ + src/ui/sensorpodstatus.ui \ src/ui/AutoTrim.ui HEADERS += \ @@ -508,6 +510,7 @@ HEADERS += \ src/QmlControls/ScreenTools.h \ src/uas/ASLUAV.h \ src/ui/energybudget.h \ + src/ui/sensorpodstatus.h \ src/ui/AutoTrim.h SOURCES += \ @@ -652,6 +655,7 @@ SOURCES += \ src/ui/toolbar/MainToolBar.cc \ src/QmlControls/ScreenTools.cc \ src/ui/energybudget.cpp \ + src/ui/sensorpodstatus.cpp \ src/uas/ASLUAV.cc \ src/ui/AutoTrim.cpp diff --git a/src/uas/ASLUAV.cc b/src/uas/ASLUAV.cc index 5ca329650a6..c1e8f7f51e0 100644 --- a/src/uas/ASLUAV.cc +++ b/src/uas/ASLUAV.cc @@ -190,6 +190,15 @@ void ASLUAV::receiveMessage(LinkInterface *link, mavlink_message_t message) //The rest of the message handling (i.e. adding data to the plots) is done elsewhere break; } + case MAVLINK_MSG_ID_SENSORPOD_STATUS: + { + mavlink_sensorpod_status_t data; + mavlink_msg_sensorpod_status_decode(&message, &data); + emit SensorpodStatusChanged(data.visensor_rate_1, data.visensor_rate_2, data.visensor_rate_3, data.visensor_rate_4, + data.recording_nodes_count,data.cpu_temp, data.free_space); + + break; + } default: { //std::cout << "msgid:"<getSystemId(), mavlink->getComponentId(), &msg, uasId, target_component, CmdID, 1, param1, param2, param3, param4, param5, param6, param7); + sendMessage(msg); + + std::cout << "ASLUAV: Command with ID #"< _mapName2DockWidget; QMap _mapUasId2HilDockWidget; diff --git a/src/ui/sensorpodstatus.cpp b/src/ui/sensorpodstatus.cpp new file mode 100644 index 00000000000..804434e38be --- /dev/null +++ b/src/ui/sensorpodstatus.cpp @@ -0,0 +1,102 @@ +#include "sensorpodstatus.h" +#include "ui_sensorpodstatus.h" +#include +#include +#include +#include +#include +#include "../uas/ASLUAV.h" +#include "UASInterface.h" +#include "UASManager.h" +#include "QGCApplication.h" + +#define RESETTIMEMS 10000 + +SensorpodStatus::SensorpodStatus(QWidget *parent) : + QWidget(parent), + ui(new Ui::SensorpodStatus), + m_scene(new QGraphicsScene(this)), + m_UpdateReset(new QTimer (this)) +{ + ui->setupUi(this); + connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(setActiveUAS(UASInterface*))); + connect(ui->PowerCycleButton, SIGNAL(clicked()), this, SLOT(PowerCycleSensorpodCmd())); +// connect(qgcApp(), SIGNAL(styleChanged(bool)), this, SLOT(styleChanged(bool))); + m_UpdateReset->setInterval(RESETTIMEMS); + m_UpdateReset->setSingleShot(false); + connect(m_UpdateReset, SIGNAL(timeout()), this, SLOT(UpdateTimerTimeout())); + if (UASManager::instance()->getActiveUAS()) + { + setActiveUAS(UASManager::instance()->getActiveUAS()); + } + m_UpdateReset->start(); +} + +SensorpodStatus::~SensorpodStatus() +{ + delete ui; + delete m_scene; + delete m_UpdateReset; +} + +void SensorpodStatus::updateSensorpodStatus(uint8_t rate1, uint8_t rate2, uint8_t rate3, uint8_t rate4, uint8_t numRecordTopics, uint8_t cpuTemp, uint16_t freeSpace) +{ + m_UpdateReset->stop(); + ui->topic1rate->setText(QString("%1 Hz").arg(rate1)); + ui->topic2rate->setText(QString("%1 Hz").arg(rate2)); + ui->topic3rate->setText(QString("%1 Hz").arg(rate3)); + ui->topic4rate->setText(QString("%1 Hz").arg(rate4)); + ui->numRecNodes->setText(QString("%1").arg(numRecordTopics)); + ui->cpuTemp->setText(QString("%1 °C").arg(cpuTemp)); + ui->freeDiskSpace->setText(QString("%1 GB").arg(freeSpace/100.0)); + m_UpdateReset->start(RESETTIMEMS); +} + + +//void EnergyBudget::resizeEvent(QResizeEvent *event) +//{ +// QWidget::resizeEvent(event); +// ui->overviewGraphicsView->fitInView(m_scene->sceneRect(), Qt::AspectRatioMode::KeepAspectRatio); +//} + +void SensorpodStatus::setActiveUAS(UASInterface *uas) +{ + //disconnect any previous uas + disconnect(this, SLOT(updateSensorpodStatus(uint8_t, uint8_t, uint8_t, uint8_t, uint8_t, uint8_t, uint16_t))); + + //connect the uas if asluas + ASLUAV *asluas = dynamic_cast(uas); + if (asluas) + { + connect(asluas, SIGNAL(SensorpodStatusChanged(uint8_t, uint8_t, uint8_t, uint8_t, uint8_t, uint8_t, uint16_t)), this, SLOT(updateSensorpodStatus(uint8_t, uint8_t, uint8_t, uint8_t, uint8_t, uint8_t, uint16_t))); + } + //else set to standard output + else + { + + } +} + +void SensorpodStatus::PowerCycleSensorpodCmd() +{ + QMessageBox::StandardButton reply; + reply = QMessageBox::question(this, tr("Sensorpod reset"), tr("Sending command to perform power cycle of sensorpod. Use this with caution! Are you sure?"), QMessageBox::Yes | QMessageBox::No); + + if (reply == QMessageBox::Yes) { + //Send the message via the currently active UAS + ASLUAV *tempUAS = (ASLUAV*) UASManager::instance()->getActiveUAS();; + if (tempUAS) tempUAS->SendCommandLongTarget(MAV_CMD_PAYLOAD_CONTROL, (uint8_t) 50, 1.0f); + } + +} + +void SensorpodStatus::UpdateTimerTimeout() +{ + ui->topic1rate->setText(QString("--")); + ui->topic2rate->setText(QString("--")); + ui->topic3rate->setText(QString("--")); + ui->topic4rate->setText(QString("--")); + ui->numRecNodes->setText(QString("--")); + ui->cpuTemp->setText(QString("--")); + ui->freeDiskSpace->setText(QString("--")); +} diff --git a/src/ui/sensorpodstatus.h b/src/ui/sensorpodstatus.h new file mode 100644 index 00000000000..530458d27eb --- /dev/null +++ b/src/ui/sensorpodstatus.h @@ -0,0 +1,39 @@ +#ifndef SENSORPODSTATUS_H +#define SENSORPODSTATUS_H + +#include +#include +#include + +namespace Ui { +class SensorpodStatus; +} + +class QGraphicsScene; +class UASInterface; +class QTimer; +class UASInterface; + +class SensorpodStatus : public QWidget +{ + Q_OBJECT + +public: + explicit SensorpodStatus(QWidget *parent = 0); + ~SensorpodStatus(); + +protected: + Ui::SensorpodStatus *ui; + QGraphicsScene *m_scene; + QTimer *m_UpdateReset; + + +protected slots: + void updateSensorpodStatus(uint8_t rate1, uint8_t rate2, uint8_t rate3, uint8_t rate4, uint8_t numRecordTopics, uint8_t cpuTemp, uint16_t freeSpace); + void setActiveUAS(UASInterface *uas); + void UpdateTimerTimeout(); + + void PowerCycleSensorpodCmd(); +}; + +#endif // SENSORPODSTATUS_H diff --git a/src/ui/sensorpodstatus.ui b/src/ui/sensorpodstatus.ui index 8456818c4bc..3e210cc4e2b 100644 --- a/src/ui/sensorpodstatus.ui +++ b/src/ui/sensorpodstatus.ui @@ -1,7 +1,7 @@ - EnergyBudget - + SensorpodStatus + 0 @@ -33,16 +33,6 @@ ROS Topic Rates - - - - Topic 4 - - - Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - - @@ -50,17 +40,24 @@ - - + + ??? + + + + + + Topic 2 + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - + ??? @@ -70,37 +67,40 @@ - - + + - ??? + Topic 3 Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - + + - Topic 3 + ??? Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - + + - ??? + Topic 4 + + + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter - - + + - Topic 2 + ??? Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -123,20 +123,13 @@ - - + + ??? - Qt::AlignCenter - - - - - - - Free disk space + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter @@ -147,13 +140,20 @@ - - + + ??? - Qt::AlignCenter + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + + + + Free disk space @@ -163,34 +163,111 @@ ??? - Qt::AlignCenter + Qt::AlignLeading|Qt::AlignLeft|Qt::AlignVCenter + + + + Qt::Vertical + + + + 20 + 40 + + + + CMD - + - 70 - 20 - 111 - 31 + 9 + 10 + 363 + 51 - - Perform a power cycle of the whole pod - - - Power Cycle - + + + + + Qt::Vertical + + + + 20 + 40 + + + + + + + + Perform a power cycle of the whole pod + + + Power Cycle Sensorpod + + + + + + + Qt::Horizontal + + + QSizePolicy::MinimumExpanding + + + + 20 + 20 + + + + + + + + Qt::Horizontal + + + QSizePolicy::MinimumExpanding + + + + 20 + 20 + + + + + + + + Qt::Vertical + + + + 20 + 40 + + + + + From 9f661ccacfa392b72f01cd298b299ddc4d181249 Mon Sep 17 00:00:00 2001 From: mantelt Date: Mon, 21 Sep 2015 11:10:19 +0200 Subject: [PATCH 4/5] cosmetic change in variable name renamed variable from quick fix name (temp) to something little bit more meaningfull --- src/ui/energybudget.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/src/ui/energybudget.cpp b/src/ui/energybudget.cpp index f6b26368a90..9899d356ea4 100644 --- a/src/ui/energybudget.cpp +++ b/src/ui/energybudget.cpp @@ -100,12 +100,12 @@ void EnergyBudget::buildGraphicsImage() qreal penWidth(40); // scale and place images - QRectF temp=m_propPixmap->boundingRect(); - m_propPixmap->setScale(this->adjustImageScale(m_scene->sceneRect(), temp )); - temp=m_cellPixmap->boundingRect(); - m_cellPixmap->setScale(this->adjustImageScale(m_scene->sceneRect(), temp )); - temp=m_batPixmap->boundingRect(); - m_batPixmap->setScale(this->adjustImageScale(m_scene->sceneRect(), temp )); + QRectF tempRectF=m_propPixmap->boundingRect(); + m_propPixmap->setScale(this->adjustImageScale(m_scene->sceneRect(), tempRectF )); + tempRectF=m_cellPixmap->boundingRect(); + m_cellPixmap->setScale(this->adjustImageScale(m_scene->sceneRect(), tempRectF )); + tempRectF=m_batPixmap->boundingRect(); + m_batPixmap->setScale(this->adjustImageScale(m_scene->sceneRect(), tempRectF )); double maxheight(std::fmax(m_propPixmap->mapRectToScene(m_propPixmap->boundingRect()).height(), m_batPixmap->mapRectToScene(m_batPixmap->boundingRect()).height())); m_propPixmap->setOffset(0.0, m_propPixmap->mapRectFromScene(m_scene->sceneRect()).height() - m_propPixmap->mapRectFromScene(QRectF(0.0,0.0,1.0,maxheight)).height()/2.0 - m_propPixmap->boundingRect().height() / 2.0); m_batPixmap->setOffset(m_batPixmap->mapRectFromScene(m_scene->sceneRect()).width() - m_batPixmap->boundingRect().width(), m_batPixmap->mapRectFromScene(m_scene->sceneRect()).height() - m_batPixmap->mapRectFromScene(QRectF(0.0, 0.0, 1.0, maxheight)).height() / 2.0 - m_batPixmap->boundingRect().height() / 2.0); From 95f9a3be5e219e7619f77a11ec51becfb9940e68 Mon Sep 17 00:00:00 2001 From: mantelt Date: Mon, 21 Sep 2015 15:25:21 +0200 Subject: [PATCH 5/5] Small layout fix Reset button is now nicely placed inside the widget. --- src/ui/sensorpodstatus.ui | 108 +++++++++----------------------------- 1 file changed, 26 insertions(+), 82 deletions(-) diff --git a/src/ui/sensorpodstatus.ui b/src/ui/sensorpodstatus.ui index 3e210cc4e2b..9585de4a790 100644 --- a/src/ui/sensorpodstatus.ui +++ b/src/ui/sensorpodstatus.ui @@ -20,7 +20,7 @@ QTabWidget::Triangular - 0 + 1 @@ -28,7 +28,7 @@ - + ROS Topic Rates @@ -189,86 +189,30 @@ CMD - - - - 9 - 10 - 363 - 51 - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - - - Perform a power cycle of the whole pod - - - Power Cycle Sensorpod - - - - - - - Qt::Horizontal - - - QSizePolicy::MinimumExpanding - - - - 20 - 20 - - - - - - - - Qt::Horizontal - - - QSizePolicy::MinimumExpanding - - - - 20 - 20 - - - - - - - - Qt::Vertical - - - - 20 - 40 - - - - - - + + + + + + 140 + 0 + + + + + 180 + 16777215 + + + + Perform a power cycle of the whole pod + + + Power Cycle Sensorpod + + + +