Commit 6dc9b706 authored by pixhawk's avatar pixhawk

Merge branch 'master' of git@pixhawk.ethz.ch:qgroundcontrol

parents 7620cd39 db00ea6e
This source diff could not be displayed because it is too large. You can view the blob instead.
This source diff could not be displayed because it is too large. You can view the blob instead.
This source diff could not be displayed because it is too large. You can view the blob instead.
......@@ -62,7 +62,8 @@ INCLUDEPATH += src \
src/input \
src/lib/qmapcontrol \
src/ui/mavlink \
src/ui/param
src/ui/param \
src/ui/watchdog
HEADERS += src/MG.h \
src/Core.h \
src/uas/UASInterface.h \
......
......@@ -713,6 +713,94 @@ void UAS::enableRawSensorFusionTransmission(bool enabled)
sendMessage(msg);
}
void UAS::enablePositionTransmission(bool enabled)
{
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
// Select the message to request from now on
stream.req_stream_id = 6;
// Select the update rate in Hz the message should be send
stream.req_message_rate = 200;
// Start / stop the message
stream.start_stop = (enabled) ? 1 : 0;
// The system which should take this command
stream.target_system = uasId;
// The component / subsystem which should take this command
stream.target_component = 0;
// Encode and send the message
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
}
void UAS::enableExtra1Transmission(bool enabled)
{
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
// Select the message to request from now on
stream.req_stream_id = 7;
// Select the update rate in Hz the message should be send
stream.req_message_rate = 200;
// Start / stop the message
stream.start_stop = (enabled) ? 1 : 0;
// The system which should take this command
stream.target_system = uasId;
// The component / subsystem which should take this command
stream.target_component = 0;
// Encode and send the message
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
}
void UAS::enableExtra2Transmission(bool enabled)
{
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
// Select the message to request from now on
stream.req_stream_id = 8;
// Select the update rate in Hz the message should be send
stream.req_message_rate = 200;
// Start / stop the message
stream.start_stop = (enabled) ? 1 : 0;
// The system which should take this command
stream.target_system = uasId;
// The component / subsystem which should take this command
stream.target_component = 0;
// Encode and send the message
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
}
void UAS::enableExtra3Transmission(bool enabled)
{
// Buffers to write data to
mavlink_message_t msg;
mavlink_request_data_stream_t stream;
// Select the message to request from now on
stream.req_stream_id = 9;
// Select the update rate in Hz the message should be send
stream.req_message_rate = 200;
// Start / stop the message
stream.start_stop = (enabled) ? 1 : 0;
// The system which should take this command
stream.target_system = uasId;
// The component / subsystem which should take this command
stream.target_component = 0;
// Encode and send the message
mavlink_msg_request_data_stream_encode(mavlink->getSystemId(), mavlink->getComponentId(), &msg, &stream);
// Send message twice to increase chance of reception
sendMessage(msg);
sendMessage(msg);
}
void UAS::setParameter(int component, QString id, float value)
{
mavlink_message_t msg;
......
......@@ -202,6 +202,10 @@ public slots:
void enableRCChannelDataTransmission(bool enabled);
void enableRawControllerDataTransmission(bool enabled);
void enableRawSensorFusionTransmission(bool enabled);
void enablePositionTransmission(bool enabled);
void enableExtra1Transmission(bool enabled);
void enableExtra2Transmission(bool enabled);
void enableExtra3Transmission(bool enabled);
/** @brief Update the system state */
void updateState();
......
......@@ -59,7 +59,7 @@ This file is part of the QGROUNDCONTROL project
* @see QMainWindow::show()
**/
MainWindow::MainWindow(QWidget *parent) : QMainWindow(parent),
settings()
settings()
{
this->hide();
this->setVisible(false);
......@@ -98,6 +98,8 @@ MainWindow::MainWindow(QWidget *parent) : QMainWindow(parent),
centerStack->addWidget(protocol);
parameters = new ParameterInterface(this);
parameters->setVisible(false);
watchdogControl = new WatchdogControl(this);
watchdogControl->setVisible(false);
QStringList* acceptList = new QStringList();
acceptList->append("roll IMU");
......@@ -435,6 +437,10 @@ void MainWindow::loadOperatorView()
container6->setWidget(detection);
addDockWidget(Qt::RightDockWidgetArea, container6);
// PROCESS CONTROL
QDockWidget* pControl = new QDockWidget(tr("Process Control"), this);
pControl->setWidget(watchdogControl);
addDockWidget(Qt::RightDockWidgetArea, pControl);
this->show();
}
......@@ -458,6 +464,7 @@ void MainWindow::loadSettingsView()
QDockWidget* container6 = new QDockWidget(tr("Onboard Parameters"), this);
container6->setWidget(parameters);
addDockWidget(Qt::RightDockWidgetArea, container6);
this->show();
}
void MainWindow::loadEngineerView()
......@@ -503,6 +510,7 @@ void MainWindow::loadMAVLinkView()
{
clearView();
centerStack->setCurrentWidget(protocol);
this->show();
}
void MainWindow::loadAllView()
......
......@@ -60,6 +60,7 @@ This file is part of the PIXHAWK project
#include "ParameterInterface.h"
#include "XMLCommProtocolWidget.h"
#include "HDDisplay.h"
#include "WatchdogControl.h"
#include "LogCompressor.h"
......@@ -146,6 +147,7 @@ protected:
XMLCommProtocolWidget* protocol;
HDDisplay* headDown1;
HDDisplay* headDown2;
WatchdogControl* watchdogControl;
// Popup widgets
JoystickWidget* joystickWidget;
......
......@@ -35,7 +35,7 @@
<x>0</x>
<y>0</y>
<width>1000</width>
<height>22</height>
<height>25</height>
</rect>
</property>
<widget class="QMenu" name="menuMGround">
......@@ -257,7 +257,7 @@
<action name="actionShow_MAVLink_view">
<property name="icon">
<iconset resource="../../mavground.qrc">
<normaloff>:/images/devices/network-wireless.svg</normaloff>:/images/devices/network-wireless.svg</iconset>
<normaloff>:/images/devices/network-wired.svg</normaloff>:/images/devices/network-wired.svg</iconset>
</property>
<property name="text">
<string>Show MAVLink view</string>
......
......@@ -12,6 +12,10 @@ QGCSensorSettingsWidget::QGCSensorSettingsWidget(UASInterface* uas, QWidget *par
connect(ui->sendControllerCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableRawControllerDataTransmission(bool)));
connect(ui->sendExtendedCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableExtendedSystemStatusTransmission(bool)));
connect(ui->sendRCCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableRCChannelDataTransmission(bool)));
connect(ui->sendPositionCheckBox, SIGNAL(toggled(bool)), mav, SLOT(enablePositionTransmission(bool)));
connect(ui->sendExtra1CheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableExtra1Transmission(bool)));
connect(ui->sendExtra2CheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableExtra2Transmission(bool)));
connect(ui->sendExtra3CheckBox, SIGNAL(toggled(bool)), mav, SLOT(enableExtra3Transmission(bool)));
}
QGCSensorSettingsWidget::~QGCSensorSettingsWidget()
......
......@@ -54,6 +54,34 @@
</property>
</widget>
</item>
<item row="4" column="0">
<widget class="QCheckBox" name="sendPositionCheckBox">
<property name="text">
<string>Send position setpoint and estimate</string>
</property>
</widget>
</item>
<item row="5" column="0">
<widget class="QCheckBox" name="sendExtra1CheckBox">
<property name="text">
<string>Send Extra1</string>
</property>
</widget>
</item>
<item row="6" column="0">
<widget class="QCheckBox" name="sendExtra2CheckBox">
<property name="text">
<string>Send Extra2</string>
</property>
</widget>
</item>
<item row="7" column="0">
<widget class="QCheckBox" name="sendExtra3CheckBox">
<property name="text">
<string>Send Extra3</string>
</property>
</widget>
</item>
</layout>
</widget>
</item>
......
......@@ -13,7 +13,7 @@
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,10,0,0,0" columnstretch="1,1,1,10">
<layout class="QGridLayout" name="gridLayout" rowstretch="0,0,100,0,0,0" columnstretch="1,1,1,100">
<property name="topMargin">
<number>6</number>
</property>
......
......@@ -2,6 +2,8 @@
#include "ui_WatchdogControl.h"
#include "PxQuadMAV.h"
#include "UASManager.h"
#include <QDebug>
WatchdogControl::WatchdogControl(QWidget *parent) :
......@@ -10,6 +12,7 @@ WatchdogControl::WatchdogControl(QWidget *parent) :
ui(new Ui::WatchdogControl)
{
ui->setupUi(this);
connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(setUAS(UASInterface*)));
}
WatchdogControl::~WatchdogControl()
......@@ -24,6 +27,8 @@ void WatchdogControl::setUAS(UASInterface* uas)
if (qmav)
{
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
// start the timeout timer
//watchdog.timeoutTimer_.reset();
qDebug() << "WATCHDOG RECEIVED";
//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
process.name_ = name.toStdString();
process.arguments_ = arguments.toStdString();
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;
}
......@@ -67,6 +74,7 @@ void WatchdogControl::updateProcess(int systemId, int watchdogId, int processId,
process.crashes_ = crashes;
process.pid_ = pid;
qDebug() << "PROCESS UPDATED";
//process.updateTimer_.reset();
//qDebug() << "<-- received mavlink_watchdog_process_status_t " << msg->sysid << " / " << payload.state << " / " << payload.muted << " / " << payload.crashes << " / " << payload.pid << std::endl;
}
......
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<author/>
<comment/>
<exportmacro/>
<class>WatchdogControl</class>
<widget class="QWidget" name="WatchdogControl">
<property name="geometry">
......@@ -15,7 +13,19 @@
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout" stretch="100,0">
<item>
<widget class="QWidget" name="mainWidget" native="true"/>
</item>
<item>
<widget class="QLabel" name="processInfoLabel">
<property name="text">
<string>0 Processes Core 1: 0% Core 2: 0%</string>
</property>
</widget>
</item>
</layout>
</widget>
<pixmapfunction/>
<resources/>
<connections/>
</ui>
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