Commit c9a7fdde authored by pixhawk's avatar pixhawk

Added link multiplexing, added several new packets

parent cd6c890e
......@@ -156,7 +156,8 @@ FORMS += src/ui/MainWindow.ui \
src/ui/designer/QGCActionButton.ui \
src/ui/QGCMAVLinkLogPlayer.ui \
src/ui/QGCWaypointListMulti.ui \
src/ui/mission/QGCCustomWaypointAction.ui
src/ui/mission/QGCCustomWaypointAction.ui \
src/ui/QGCUDPLinkConfiguration.ui
INCLUDEPATH += src \
src/ui \
......@@ -266,7 +267,8 @@ HEADERS += src/MG.h \
src/comm/MAVLinkSimulationWaypointPlanner.h \
src/comm/MAVLinkSimulationMAV.h \
src/uas/QGCMAVLinkUASFactory.h \
src/ui/QGCWaypointListMulti.h
src/ui/QGCWaypointListMulti.h \
src/ui/QGCUDPLinkConfiguration.h
# Google Earth is only supported on Mac OS and Windows with Visual Studio Compiler
macx|win32-msvc2008: {
......@@ -391,7 +393,8 @@ SOURCES += src/main.cc \
src/comm/MAVLinkSimulationWaypointPlanner.cc \
src/comm/MAVLinkSimulationMAV.cc \
src/uas/QGCMAVLinkUASFactory.cc \
src/ui/QGCWaypointListMulti.cc
src/ui/QGCWaypointListMulti.cc \
src/ui/QGCUDPLinkConfiguration.cc
macx|win32-msvc2008: {
SOURCES += src/ui/map3D/QGCGoogleEarthView.cc
......
......@@ -74,7 +74,8 @@ void MAVLinkProtocol::loadSettings()
settings.sync();
settings.beginGroup("QGC_MAVLINK_PROTOCOL");
enableHeartbeats(settings.value("HEARTBEATS_ENABLED", m_heartbeatsEnabled).toBool());
enableVersionCheck(settings.value("VERION_CHECK_ENABLED", m_enable_version_check).toBool());
enableVersionCheck(settings.value("VERSION_CHECK_ENABLED", m_enable_version_check).toBool());
enableMultiplexing(settings.value("MULTIPLEXING_ENABLED", m_multiplexingEnabled).toBool());
// Only set logfile if there is a name present in settings
if (settings.contains("LOGFILE_NAME") && m_logfile == NULL)
......@@ -100,7 +101,8 @@ void MAVLinkProtocol::storeSettings()
settings.beginGroup("QGC_MAVLINK_PROTOCOL");
settings.setValue("HEARTBEATS_ENABLED", m_heartbeatsEnabled);
settings.setValue("LOGGING_ENABLED", m_loggingEnabled);
settings.setValue("VERION_CHECK_ENABLED", m_enable_version_check);
settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
settings.setValue("MULTIPLEXING_ENABLED", m_multiplexingEnabled);
settings.setValue("GCS_SYSTEM_ID", systemId);
if (m_logfile)
{
......@@ -298,6 +300,21 @@ void MAVLinkProtocol::receiveBytes(LinkInterface* link, QByteArray b)
// kind of inefficient, but no issue for a groundstation pc.
// It buys as reentrancy for the whole code over all threads
emit messageReceived(link, message);
// Multiplex message if enabled
if (m_multiplexingEnabled)
{
// Get all links connected to this unit
QList<LinkInterface*> links = LinkManager::instance()->getLinksForProtocol(this);
// Emit message on all links that are currently connected
foreach (LinkInterface* currLink, links)
{
// Only forward this message to the other links,
// not the link the message was received on
if (currLink != link) sendMessage(currLink, message);
}
}
}
}
}
......@@ -388,6 +405,15 @@ void MAVLinkProtocol::enableHeartbeats(bool enabled)
emit heartbeatChanged(enabled);
}
void MAVLinkProtocol::enableMultiplexing(bool enabled)
{
bool changed = false;
if (enabled != m_multiplexingEnabled) changed = true;
m_multiplexingEnabled = enabled;
if (changed) emit multiplexingChanged(m_multiplexingEnabled);
}
void MAVLinkProtocol::enableLogging(bool enabled)
{
bool changed = false;
......@@ -447,21 +473,6 @@ void MAVLinkProtocol::enableVersionCheck(bool enabled)
emit versionCheckChanged(enabled);
}
bool MAVLinkProtocol::heartbeatsEnabled(void)
{
return m_heartbeatsEnabled;
}
bool MAVLinkProtocol::loggingEnabled(void)
{
return m_loggingEnabled;
}
bool MAVLinkProtocol::versionCheckEnabled(void)
{
return m_enable_version_check;
}
/**
* The default rate is 1 Hertz.
*
......
......@@ -66,11 +66,13 @@ public:
/** @brief The auto heartbeat emission rate in Hertz */
int getHeartbeatRate();
/** @brief Get heartbeat state */
bool heartbeatsEnabled(void);
bool heartbeatsEnabled() const { return m_heartbeatsEnabled; }
/** @brief Get logging state */
bool loggingEnabled(void);
bool loggingEnabled() const { return m_loggingEnabled; }
/** @brief Get protocol version check state */
bool versionCheckEnabled(void);
bool versionCheckEnabled() const { return m_enable_version_check; }
/** @brief Get the multiplexing state */
bool multiplexingEnabled() const { return m_multiplexingEnabled; }
/** @brief Get the protocol version */
int getVersion() { return MAVLINK_VERSION; }
/** @brief Get the name of the packet log file */
......@@ -94,6 +96,9 @@ public slots:
/** @brief Enable/disable binary packet logging */
void enableLogging(bool enabled);
/** @brief Enabled/disable packet multiplexing */
void enableMultiplexing(bool enabled);
/** @brief Set log file name */
void setLogfileName(const QString& filename);
......@@ -113,6 +118,7 @@ protected:
int heartbeatRate; ///< Heartbeat rate, controls the timer interval
bool m_heartbeatsEnabled; ///< Enabled/disable heartbeat emission
bool m_loggingEnabled; ///< Enable/disable packet logging
bool m_multiplexingEnabled; ///< Enable/disable packet multiplexing
QFile* m_logfile; ///< Logfile
bool m_enable_version_check; ///< Enable checking of version match of MAV and QGC
QMutex receiveMutex; ///< Mutex to protect receiveBytes function
......@@ -131,6 +137,8 @@ signals:
void heartbeatChanged(bool heartbeats);
/** @brief Emitted if logging is started / stopped */
void loggingChanged(bool enabled);
/** @brief Emitted if multiplexing is started / stopped */
void multiplexingChanged(bool enabled);
/** @brief Emitted if version check is enabled / disabled */
void versionCheckChanged(bool enabled);
/** @brief Emitted if a message from the protocol should reach the user */
......
......@@ -619,7 +619,8 @@ void MAVLinkSimulationLink::mainloop()
uint8_t gpsLock = 2;
uint8_t visLock = 3;
uint8_t posLock = qMax(gpsLock, visLock);
messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, attControl, posXYControl, posZControl, posYawControl);
uint8_t ahrsHealth = 240;
messageSize = mavlink_msg_control_status_pack(systemId, componentId, &msg, posLock, visLock, gpsLock, ahrsHealth, attControl, posXYControl, posZControl, posYawControl);
#endif
bufferlength = mavlink_msg_to_send_buffer(buffer, &msg);
......
......@@ -162,6 +162,29 @@ void MAVLinkSimulationMAV::mainloop()
mavlink_msg_sys_status_encode(systemid, MAV_COMP_ID_IMU, &msg, &status);
link->sendMAVLinkMessage(&msg);
timer10Hz = 5;
// VFR HUD
mavlink_vfr_hud_t hud;
hud.airspeed = 10;
hud.groundspeed = 9;
hud.alt = 123;
hud.heading = 90;
hud.climb = 0.1;
hud.throttle = 90;
mavlink_msg_vfr_hud_encode(systemid, MAV_COMP_ID_IMU, &msg, &hud);
link->sendMAVLinkMessage(&msg);
// NAV CONTROLLER
mavlink_nav_controller_output_t nav;
nav.nav_roll = roll;
nav.nav_pitch = pitch;
nav.nav_bearing = yaw;
nav.target_bearing = yaw;
nav.wp_dist = 2;
nav.alt_error = 0.5;
// xtrack
mavlink_msg_nav_controller_output_encode(systemid, MAV_COMP_ID_IMU, &msg, &nav);
link->sendMAVLinkMessage(&msg);
}
// 25 Hz execution
......
......@@ -78,9 +78,32 @@ void UDPLink::setAddress(QString address)
//socket->setLocalAddress(QHostAddress(address));
}
void UDPLink::setPort(quint16 port)
void UDPLink::setPort(int port)
{
this->port = port;
disconnect();
connect();
}
/**
* @param host Hostname in standard formatting, e.g. localhost:14551 or 192.168.1.1:14551
*/
void UDPLink::addHost(const QString& host)
{
if (host.contains(":"))
{
// Add host
hosts->append(QHostAddress(host.split(":").first()));
// Set port according to user input
ports->append(host.split(":").last().toInt());
}
else
{
// Add host
hosts->append(QHostAddress(host));
// Set port according to default (this port)
ports->append(port);
}
}
......
......@@ -51,6 +51,7 @@ public:
bool isConnected();
qint64 bytesAvailable();
int getPort() const { return port; }
/**
* @brief The human readable port name
......@@ -82,7 +83,9 @@ public:
public slots:
void setAddress(QString address);
void setPort(quint16 port);
void setPort(int port);
/** @brief Add a new host to broadcast messages to */
void addHost(const QString& host);
// void readPendingDatagrams();
void readBytes();
......
......@@ -162,13 +162,13 @@ void UAS::receiveMessageNamedValue(const mavlink_message_t& message)
{
mavlink_named_value_float_t val;
mavlink_msg_named_value_float_decode(&message, &val);
emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), val.value, getUnixTime(0));
emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), val.value, getUnixTime());
}
else if (message.msgid == MAVLINK_MSG_ID_NAMED_VALUE_INT)
{
mavlink_named_value_int_t val;
mavlink_msg_named_value_int_decode(&message, &val);
emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), (float)val.value, getUnixTime(0));
emit valueChanged(this->getUASID(), QString((char *)val.name), tr("raw"), val.value, getUnixTime());
}
}
......@@ -424,6 +424,37 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
emit attitudeSpeedChanged(uasId, attitude.rollspeed, attitude.pitchspeed, attitude.yawspeed, time);
}
break;
case MAVLINK_MSG_ID_VFR_HUD:
{
mavlink_vfr_hud_t hud;
mavlink_msg_vfr_hud_decode(&message, &hud);
quint64 time = getUnixTime();
// Display updated values
emit valueChanged(uasId, "airspeed", "m/s", hud.airspeed, time);
emit valueChanged(uasId, "groundspeed", "m/s", hud.groundspeed, time);
emit valueChanged(uasId, "altitude", "m", hud.alt, time);
emit valueChanged(uasId, "heading", "deg", hud.heading, time);
emit valueChanged(uasId, "climbrate", "m/s", hud.climb, time);
emit valueChanged(uasId, "throttle", "m/s", hud.throttle, time);
emit thrustChanged(this, hud.throttle/100.0);
}
break;
case MAVLINK_MSG_ID_NAV_CONTROLLER_OUTPUT:
{
mavlink_nav_controller_output_t nav;
mavlink_msg_nav_controller_output_decode(&message, &nav);
quint64 time = getUnixTime();
// Update UI
emit valueChanged(uasId, "nav roll", "deg", nav.nav_roll, time);
emit valueChanged(uasId, "nav pitch", "deg", nav.nav_pitch, time);
emit valueChanged(uasId, "nav bearing", "deg", nav.nav_bearing, time);
emit valueChanged(uasId, "target bearing", "deg", nav.target_bearing, time);
emit valueChanged(uasId, "wp dist", "m", nav.wp_dist, time);
emit valueChanged(uasId, "alt err", "m", nav.alt_error, time);
emit valueChanged(uasId, "airspeed err", "m/s", nav.alt_error, time);
//emit valueChanged(uasId, "xtrack err", "m", nav.xtrack_error, time);
}
break;
case MAVLINK_MSG_ID_LOCAL_POSITION:
//std::cerr << std::endl;
//std::cerr << "Decoded attitude message:" << " roll: " << std::dec << mavlink_msg_attitude_get_roll(message.payload) << " pitch: " << mavlink_msg_attitude_get_pitch(message.payload) << " yaw: " << mavlink_msg_attitude_get_yaw(message.payload) << std::endl;
......@@ -736,7 +767,6 @@ void UAS::receiveMessage(LinkInterface* link, mavlink_message_t message)
break;
case MAVLINK_MSG_ID_SERVO_OUTPUT_RAW:
{
qDebug() << "Received servo raw message";
mavlink_servo_output_raw_t servos;
mavlink_msg_servo_output_raw_decode(&message, &servos);
quint64 time = getUnixTime(0);
......
......@@ -316,8 +316,8 @@ signals:
void imageStarted(quint64 timestamp);
protected:
/** @brief Get the UNIX timestamp in microseconds */
quint64 getUnixTime(quint64 time);
/** @brief Get the UNIX timestamp in milliseconds */
quint64 getUnixTime(quint64 time=0);
protected slots:
/** @brief Write settings to disk */
......
......@@ -47,6 +47,7 @@ This file is part of the QGROUNDCONTROL project
#endif
#include "MAVLinkProtocol.h"
#include "MAVLinkSettingsWidget.h"
#include "QGCUDPLinkConfiguration.h"
#include "LinkManager.h"
CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolInterface* protocol, QWidget *parent, Qt::WindowFlags flags) : QWidget(parent, flags)
......@@ -57,20 +58,24 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
ui.setupUi(this);
// add link types
ui.linkType->addItem("Serial",QGC_LINK_SERIAL);
ui.linkType->addItem("UDP",QGC_LINK_UDP);
ui.linkType->addItem("Simulation",QGC_LINK_SIMULATION);
ui.linkType->addItem("Serial Forwarding",QGC_LINK_FORWARDING);
ui.linkType->addItem(tr("Serial"), QGC_LINK_SERIAL);
ui.linkType->addItem(tr("UDP"), QGC_LINK_UDP);
ui.linkType->addItem(tr("Simulation"), QGC_LINK_SIMULATION);
ui.linkType->addItem(tr("Opal-RT Link"), QGC_LINK_OPAL);
ui.linkType->setEditable(false);
//ui.linkType->setEnabled(false);
ui.connectionType->addItem("MAVLink", QGC_PROTOCOL_MAVLINK);
ui.connectionType->addItem("GPS NMEA", QGC_PROTOCOL_NMEA);
//ui.connectionType->addItem("GPS NMEA", QGC_PROTOCOL_NMEA);
// Create action to open this menu
// Create configuration action for this link
// Connect the current UAS
action = new QAction(QIcon(":/images/devices/network-wireless.svg"), "", link);
action = new QAction(QIcon(":/images/devices/network-wireless.svg"), "", this);
LinkManager::instance()->add(link);
action->setData(LinkManager::instance()->getLinks().indexOf(link));
action->setEnabled(true);
action->setVisible(true);
setLinkName(link->getName());
connect(action, SIGNAL(triggered()), this, SLOT(show()));
......@@ -110,17 +115,24 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
layout->addWidget(conf);
ui.linkGroupBox->setLayout(layout);
ui.linkGroupBox->setTitle(tr("Serial Link"));
ui.linkType->setCurrentIndex(0);
//ui.linkGroupBox->setTitle(link->getName());
//connect(link, SIGNAL(nameChanged(QString)), ui.linkGroupBox, SLOT(setTitle(QString)));
}
UDPLink* udp = dynamic_cast<UDPLink*>(link);
if (udp != 0)
{
QWidget* conf = new QGCUDPLinkConfiguration(udp, this);
QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox);
layout->addWidget(conf);
ui.linkGroupBox->setLayout(layout);
ui.linkGroupBox->setTitle(tr("UDP Link"));
ui.linkType->setCurrentIndex(1);
}
MAVLinkSimulationLink* sim = dynamic_cast<MAVLinkSimulationLink*>(link);
if (sim != 0)
{
ui.linkType->setCurrentIndex(2);
ui.linkGroupBox->setTitle(tr("MAVLink Simulation Link"));
}
#ifdef OPAL_RT
......@@ -131,6 +143,7 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn
QBoxLayout* layout = new QBoxLayout(QBoxLayout::LeftToRight, ui.linkGroupBox);
layout->addWidget(conf);
ui.linkGroupBox->setLayout(layout);
ui.linkType->setCurrentIndex(3);
ui.linkGroupBox->setTitle(tr("Opal-RT Link"));
}
#endif
......@@ -201,10 +214,9 @@ void CommConfigurationWindow::setConnection()
void CommConfigurationWindow::setLinkName(QString name)
{
Q_UNUSED(name); // FIXME
action->setText(tr("Configure ") + link->getName());
action->setStatusTip(tr("Configure ") + link->getName());
this->window()->setWindowTitle(tr("Settings for ") + this->link->getName());
action->setText(tr("%1 Settings").arg(name));
action->setStatusTip(tr("Adjust setting for link %1").arg(name));
this->window()->setWindowTitle(tr("Settings for %1").arg(name));
}
void CommConfigurationWindow::remove()
......
......@@ -44,7 +44,8 @@ enum qgc_link_t
QGC_LINK_SERIAL,
QGC_LINK_UDP,
QGC_LINK_SIMULATION,
QGC_LINK_FORWARDING
QGC_LINK_FORWARDING,
QGC_LINK_OPAL
};
enum qgc_protocol_t
......
......@@ -48,6 +48,7 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
m_ui->heartbeatCheckBox->setChecked(protocol->heartbeatsEnabled());
m_ui->loggingCheckBox->setChecked(protocol->loggingEnabled());
m_ui->versionCheckBox->setChecked(protocol->versionCheckEnabled());
m_ui->multiplexingCheckBox->setChecked(protocol->multiplexingEnabled());
m_ui->systemIdSpinBox->setValue(protocol->getSystemId());
// Connect actions
......@@ -59,6 +60,7 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
connect(m_ui->versionCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableVersionCheck(bool)));
connect(m_ui->logFileButton, SIGNAL(clicked()), this, SLOT(chooseLogfileName()));
connect(m_ui->systemIdSpinBox, SIGNAL(valueChanged(int)), protocol, SLOT(setSystemId(int)));
connect(m_ui->multiplexingCheckBox, SIGNAL(toggled(bool)), protocol, SLOT(enableMultiplexing(bool)));
// Update values
m_ui->versionLabel->setText(tr("MAVLINK_VERSION: %1").arg(protocol->getVersion()));
......@@ -73,6 +75,15 @@ MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget
m_ui->logFileLabel->setVisible(protocol->loggingEnabled());
connect(protocol, SIGNAL(loggingChanged(bool)), m_ui->logFileButton, SLOT(setVisible(bool)));
m_ui->logFileButton->setVisible(protocol->loggingEnabled());
connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterCheckBox, SLOT(setVisible(bool)));
m_ui->multiplexingFilterCheckBox->setVisible(protocol->multiplexingEnabled());
connect(protocol, SIGNAL(multiplexingChanged(bool)), m_ui->multiplexingFilterLineEdit, SLOT(setVisible(bool)));
m_ui->multiplexingFilterLineEdit->setVisible(protocol->multiplexingEnabled());
// TODO implement filtering
// and then remove these two lines
m_ui->multiplexingFilterCheckBox->setVisible(false);
m_ui->multiplexingFilterLineEdit->setVisible(false);
// Update settings
m_ui->loggingCheckBox->setChecked(protocol->loggingEnabled());
......
......@@ -7,7 +7,7 @@
<x>0</x>
<y>0</y>
<width>431</width>
<height>243</height>
<height>256</height>
</rect>
</property>
<property name="windowTitle">
......@@ -21,14 +21,14 @@
</property>
</widget>
</item>
<item row="2" column="0" colspan="3">
<item row="6" column="0" colspan="3">
<widget class="QCheckBox" name="loggingCheckBox">
<property name="text">
<string>Log all MAVLink packets</string>
</property>
</widget>
</item>
<item row="4" column="0">
<item row="8" column="0">
<spacer name="logFileSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
......@@ -44,14 +44,14 @@
</property>
</spacer>
</item>
<item row="5" column="0" colspan="3">
<item row="9" column="0" colspan="3">
<widget class="QCheckBox" name="versionCheckBox">
<property name="text">
<string>Only accept MAVs with same protocol version</string>
</property>
</widget>
</item>
<item row="6" column="0">
<item row="10" column="0">
<spacer name="versionSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
......@@ -64,21 +64,21 @@
</property>
</spacer>
</item>
<item row="6" column="1" colspan="2">
<item row="10" column="1" colspan="2">
<widget class="QLabel" name="versionLabel">
<property name="text">
<string>MAVLINK_VERSION: </string>
</property>
</widget>
</item>
<item row="4" column="1">
<item row="8" column="1">
<widget class="QLabel" name="logFileLabel">
<property name="text">
<string>Logfile name</string>
</property>
</widget>
</item>
<item row="4" column="2">
<item row="8" column="2">
<widget class="QPushButton" name="logFileButton">
<property name="text">
<string>Select..</string>
......@@ -114,6 +114,43 @@
</property>
</widget>
</item>
<item row="5" column="0">
<spacer name="multiplexingFilterSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeType">
<enum>QSizePolicy::MinimumExpanding</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="5" column="1" colspan="2">
<widget class="QLineEdit" name="multiplexingFilterLineEdit">
<property name="text">
<string>Enter a comma-separated list of allowed packets</string>
</property>
</widget>
</item>
<item row="4" column="0" colspan="3">
<widget class="QCheckBox" name="multiplexingFilterCheckBox">
<property name="text">
<string>Filter multiplexed packets: Only forward selected IDs</string>
</property>
</widget>
</item>
<item row="3" column="0" colspan="3">
<widget class="QCheckBox" name="multiplexingCheckBox">
<property name="text">
<string>Enable Multiplexing: Forward packets to all other links</string>
</property>
</widget>
</item>
</layout>
</widget>
<resources/>
......
......@@ -406,8 +406,9 @@ void MainWindow::buildPxWidgets()
acceptList->append("-60,pitchspeed d/s,deg/s,+60,s");
acceptList->append("-60,yawspeed d/s,deg/s,+60,s");
acceptList->append("0,airspeed,m/s,30");
acceptList->append("0,gpsspeed,m/s,30");
acceptList->append("0,truespeed,m/s,30");
acceptList->append("0,groundspeed,m/s,30");
acceptList->append("0,climbrate,m/s,30");
acceptList->append("0,throttle,m/s,100");
//FIXME: memory of acceptList2 will never be freed again
QStringList* acceptList2 = new QStringList();
......@@ -1440,7 +1441,8 @@ void MainWindow::addLink(LinkInterface *link)
LinkManager::instance()->addProtocol(link, mavlink);
CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this);
ui.menuNetwork->addAction(commWidget->getAction());
QAction* action = commWidget->getAction();
ui.menuNetwork->addAction(action);
// Error handling
connect(link, SIGNAL(communicationError(QString,QString)), this, SLOT(showCriticalMessage(QString,QString)), Qt::QueuedConnection);
......
......@@ -64,6 +64,7 @@
</property>
<addaction name="actionSelectStylesheet"/>
<addaction name="actionReloadStylesheet"/>
<addaction name="actionSettings"/>
</widget>
<addaction name="actionJoystick_Settings"/>
<addaction name="actionSimulate"/>
......@@ -431,6 +432,11 @@
<string>Meta+R</string>
</property>
</action>
<action name="actionSettings">
<property name="text">
<string>Settings</string>
</property>
</action>
</widget>
<layoutdefault spacing="6" margin="11"/>
<resources>
......
#include <QInputDialog>
#include "QGCUDPLinkConfiguration.h"
#include "ui_QGCUDPLinkConfiguration.h"
QGCUDPLinkConfiguration::QGCUDPLinkConfiguration(UDPLink* link, QWidget *parent) :
QWidget(parent),
link(link),
ui(new Ui::QGCUDPLinkConfiguration)
{
ui->setupUi(this);
ui->portSpinBox->setValue(link->getPort());
connect(ui->portSpinBox, SIGNAL(valueChanged(int)), link, SLOT(setPort(int)));
connect(ui->addIPButton, SIGNAL(clicked()), this, SLOT(addHost()));
}
QGCUDPLinkConfiguration::~QGCUDPLinkConfiguration()
{
delete ui;
}
void QGCUDPLinkConfiguration::changeEvent(QEvent *e)
{
QWidget::changeEvent(e);
switch (e->type()) {
case QEvent::LanguageChange:
ui->retranslateUi(this);
break;
default:
break;
}
}
void QGCUDPLinkConfiguration::addHost()
{
bool ok;
QString hostName = QInputDialog::getText(this, tr("Add a new IP address / hostname to MAVLink"),
tr("Host (hostname:port):"), QLineEdit::Normal,
"localhost:14555", &ok);
if (ok && !hostName.isEmpty())
link->addHost(hostName);
}
#ifndef QGCUDPLINKCONFIGURATION_H
#define QGCUDPLINKCONFIGURATION_H
#include <QWidget>
#include "UDPLink.h"
namespace Ui {
class QGCUDPLinkConfiguration;
}
class QGCUDPLinkConfiguration : public QWidget
{
Q_OBJECT
public:
explicit QGCUDPLinkConfiguration(UDPLink* link, QWidget *parent = 0);
~QGCUDPLinkConfiguration();
public slots:
void addHost();
protected:
void changeEvent(QEvent *e);
UDPLink* link; ///< UDP link instance this widget configures
private:
Ui::QGCUDPLinkConfiguration *ui;
};
#endif // QGCUDPLINKCONFIGURATION_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>QGCUDPLinkConfiguration</class>
<widget class="QWidget" name="QGCUDPLinkConfiguration">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>400</width>
<height>300</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QFormLayout" name="formLayout">
<item row="0" column="0">
<widget class="QLabel" name="portLabel">
<property name="text">
<string>UDP Port</string>
</property>
</widget>
</item>
<item row="0" column="1">
<widget class="QSpinBox" name="portSpinBox">
<property name="minimum">
<number>3000</number>
</property>
<property name="maximum">
<number>100000</number>
</property>
</widget>
</item>
<item row="1" column="0">
<widget class="QLabel" name="label">
<property name="text">
<string>Add remote communication target</string>
</property>
</widget>
</item>
<item row="1" column="1">
<widget class="QPushButton" name="addIPButton">
<property name="text">
<string>Add IP</string>
</property>
</widget>
</item>
</layout>
</widget>
<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