Commit d3d03e15 authored by Don Gagne's avatar Don Gagne

Remove unused code

parent 238e4d19
......@@ -246,7 +246,6 @@ FORMS += \
src/ui/uas/UASMessageView.ui \
src/ui/Linechart.ui \
src/ui/MultiVehicleDockWidget.ui \
src/ui/MAVLinkSettingsWidget.ui \
src/ui/QGCDataPlot2D.ui \
src/ui/QGCHilConfiguration.ui \
src/ui/QGCHilFlightGearConfiguration.ui \
......@@ -383,7 +382,6 @@ HEADERS += \
src/ui/linechart/ScrollZoomer.h \
src/ui/MainWindow.h \
src/ui/MAVLinkDecoder.h \
src/ui/MAVLinkSettingsWidget.h \
src/ui/MultiVehicleDockWidget.h \
src/ui/QGCMAVLinkLogPlayer.h \
src/ui/QGCMapRCToParamDialog.h \
......@@ -520,7 +518,6 @@ SOURCES += \
src/uas/FileManager.cc \
src/ui/uas/QGCUnconnectedInfoWidget.cc \
src/ui/MAVLinkDecoder.cc \
src/ui/MAVLinkSettingsWidget.cc \
src/ui/QGCMapRCToParamDialog.cpp \
src/comm/LogReplayLink.cc \
src/QGCFileDialog.cc \
......
......@@ -52,7 +52,6 @@ const char* MAVLinkProtocol::_logFileExtension = "mavlink"; ///< Ext
MAVLinkProtocol::MAVLinkProtocol(QGCApplication* app)
: QGCTool(app)
, m_multiplexingEnabled(false)
, m_authEnabled(false)
, m_enable_version_check(true)
, m_paramRetransmissionTimeout(350)
, m_paramRewriteTimeout(500)
......@@ -95,7 +94,6 @@ void MAVLinkProtocol::setToolbox(QGCToolbox *toolbox)
qRegisterMetaType<mavlink_message_t>("mavlink_message_t");
m_authKey = "xxxxxxxxxxxxxxxxxxxxxxxxxxxxxxxx";
loadSettings();
// All the *Counter variables are not initialized here, as they should be initialized
......@@ -135,10 +133,6 @@ void MAVLinkProtocol::loadSettings()
systemId = temp;
}
// Set auth key
m_authKey = settings.value("GCS_AUTH_KEY", m_authKey).toString();
enableAuth(settings.value("GCS_AUTH_ENABLED", m_authEnabled).toBool());
// Parameter interface settings
bool ok;
temp = settings.value("PARAMETER_RETRANSMISSION_TIMEOUT", m_paramRetransmissionTimeout).toInt(&ok);
......@@ -157,8 +151,6 @@ void MAVLinkProtocol::storeSettings()
settings.setValue("VERSION_CHECK_ENABLED", m_enable_version_check);
settings.setValue("MULTIPLEXING_ENABLED", m_multiplexingEnabled);
settings.setValue("GCS_SYSTEM_ID", systemId);
settings.setValue("GCS_AUTH_KEY", m_authKey);
settings.setValue("GCS_AUTH_ENABLED", m_authEnabled);
// Parameter interface settings
settings.setValue("PARAMETER_RETRANSMISSION_TIMEOUT", m_paramRetransmissionTimeout);
settings.setValue("PARAMETER_REWRITE_TIMEOUT", m_paramRewriteTimeout);
......@@ -489,16 +481,6 @@ void MAVLinkProtocol::enableMultiplexing(bool enabled)
if (changed) emit multiplexingChanged(m_multiplexingEnabled);
}
void MAVLinkProtocol::enableAuth(bool enable)
{
bool changed = false;
m_authEnabled = enable;
if (m_authEnabled != enable) {
changed = true;
}
if (changed) emit authChanged(m_authEnabled);
}
void MAVLinkProtocol::enableParamGuard(bool enabled)
{
if (enabled != m_paramGuardEnabled) {
......
......@@ -68,18 +68,10 @@ public:
bool multiplexingEnabled() const {
return m_multiplexingEnabled;
}
/** @brief Get the authentication state */
bool getAuthEnabled() {
return m_authEnabled;
}
/** @brief Get the protocol version */
int getVersion() {
return MAVLINK_VERSION;
}
/** @brief Get the auth key */
QString getAuthKey() {
return m_authKey;
}
/** @brief Get state of parameter retransmission */
bool paramGuardEnabled() {
return m_paramGuardEnabled;
......@@ -160,14 +152,6 @@ public slots:
/** @brief Enable / disable version check */
void enableVersionCheck(bool enabled);
/** @brief Enable / disable authentication */
void enableAuth(bool enable);
/** @brief Set authentication token */
void setAuthKey(QString key) {
m_authKey = key;
}
/** @brief Load protocol settings */
void loadSettings();
/** @brief Store protocol settings */
......@@ -183,8 +167,6 @@ public slots:
protected:
bool m_multiplexingEnabled; ///< Enable/disable packet multiplexing
bool m_authEnabled; ///< Enable authentication token broadcast
QString m_authKey; ///< Authentication key
bool m_enable_version_check; ///< Enable checking of version match of MAV and QGC
int m_paramRetransmissionTimeout; ///< Timeout for parameter retransmission
int m_paramRewriteTimeout; ///< Timeout for sending re-write request
......@@ -209,10 +191,6 @@ signals:
void messageReceived(LinkInterface* link, mavlink_message_t message);
/** @brief Emitted if multiplexing is started / stopped */
void multiplexingChanged(bool enabled);
/** @brief Emitted if authentication support is enabled / disabled */
void authKeyChanged(QString key);
/** @brief Authentication changed */
void authChanged(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 */
......
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
/**
* @file
* @brief Implementation of MAVLinkSettingsWidget
* @author Lorenz Meier <mail@qgroundcontrol.org>
*/
#include <QFileInfo>
#include <QStandardPaths>
#include "MAVLinkSettingsWidget.h"
#include "LinkManager.h"
#include "UDPLink.h"
#include "QGCApplication.h"
#include "ui_MAVLinkSettingsWidget.h"
#include <QSettings>
MAVLinkSettingsWidget::MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget *parent) :
QWidget(parent),
protocol(protocol),
m_ui(new Ui::MAVLinkSettingsWidget)
{
m_ui->setupUi(this);
m_ui->gridLayout->setAlignment(Qt::AlignTop);
// AUTH
m_ui->droneOSCheckBox->setChecked(protocol->getAuthEnabled());
QSettings settings;
m_ui->droneOSComboBox->setCurrentIndex(m_ui->droneOSComboBox->findText(settings.value("DRONELINK_HOST", "dronelink.io:14555").toString()));
m_ui->droneOSLineEdit->setText(protocol->getAuthKey());
// Initialize state
m_ui->versionCheckBox->setChecked(protocol->versionCheckEnabled());
m_ui->multiplexingCheckBox->setChecked(protocol->multiplexingEnabled());
m_ui->systemIdSpinBox->setValue(protocol->getSystemId());
m_ui->paramGuardCheckBox->setChecked(protocol->paramGuardEnabled());
m_ui->paramRetransmissionSpinBox->setValue(protocol->getParamRetransmissionTimeout());
m_ui->paramRewriteSpinBox->setValue(protocol->getParamRewriteTimeout());
m_ui->actionGuardCheckBox->setChecked(protocol->actionGuardEnabled());
m_ui->actionRetransmissionSpinBox->setValue(protocol->getActionRetransmissionTimeout());
// Version check
connect(protocol, &MAVLinkProtocol::versionCheckChanged, m_ui->versionCheckBox, &QCheckBox::setChecked);
connect(m_ui->versionCheckBox, &QCheckBox::toggled, protocol, &MAVLinkProtocol::enableVersionCheck);
// System ID
connect(protocol, &MAVLinkProtocol::systemIdChanged, m_ui->systemIdSpinBox, &QSpinBox::setValue);
connect(m_ui->systemIdSpinBox,static_cast<void (QSpinBox::*)(int)>(&QSpinBox::valueChanged), protocol, &MAVLinkProtocol::setSystemId);
// Multiplexing
connect(protocol, &MAVLinkProtocol::multiplexingChanged, m_ui->multiplexingCheckBox, &QCheckBox::setChecked);
connect(m_ui->multiplexingCheckBox, &QCheckBox::toggled, protocol, &MAVLinkProtocol::enableMultiplexing);
// Parameter guard
connect(protocol, &MAVLinkProtocol::paramGuardChanged, m_ui->paramGuardCheckBox, &QCheckBox::setChecked);
connect(m_ui->paramGuardCheckBox, &QCheckBox::toggled, protocol, &MAVLinkProtocol::enableParamGuard);
connect(protocol, &MAVLinkProtocol::paramRetransmissionTimeoutChanged, m_ui->paramRetransmissionSpinBox, &QSpinBox::setValue);
connect(m_ui->paramRetransmissionSpinBox, static_cast<void (QSpinBox::*)(int)>(&QSpinBox::valueChanged), protocol, &MAVLinkProtocol::setParamRetransmissionTimeout);
connect(protocol, &MAVLinkProtocol::paramRewriteTimeoutChanged, m_ui->paramRewriteSpinBox, &QSpinBox::setValue);
connect(m_ui->paramRewriteSpinBox, static_cast<void (QSpinBox::*)(int)>(&QSpinBox::valueChanged), protocol, &MAVLinkProtocol::setParamRewriteTimeout);
// Action guard
connect(protocol, &MAVLinkProtocol::actionGuardChanged, m_ui->actionGuardCheckBox, &QCheckBox::setChecked);
connect(m_ui->actionGuardCheckBox, &QCheckBox::toggled, protocol, &MAVLinkProtocol::enableActionGuard);
connect(protocol, &MAVLinkProtocol::actionRetransmissionTimeoutChanged, m_ui->actionRetransmissionSpinBox, &QSpinBox::setValue);
connect(m_ui->actionRetransmissionSpinBox, static_cast<void (QSpinBox::*)(int)>(&QSpinBox::valueChanged), protocol, &MAVLinkProtocol::setActionRetransmissionTimeout);
// MAVLink AUTH
connect(protocol, &MAVLinkProtocol::authChanged, m_ui->droneOSCheckBox, &QCheckBox::setChecked);
connect(m_ui->droneOSCheckBox, &QCheckBox::toggled, this, &MAVLinkSettingsWidget::enableDroneOS);
connect(protocol, &MAVLinkProtocol::authKeyChanged, m_ui->droneOSLineEdit, &QLineEdit::setText);
connect(m_ui->droneOSLineEdit, &QLineEdit::textChanged, this, &MAVLinkSettingsWidget::setDroneOSKey);
// Drone OS
connect(m_ui->droneOSComboBox, static_cast<void (QComboBox::*)(const QString&)>(&QComboBox::currentIndexChanged), this, &MAVLinkSettingsWidget::setDroneOSHost);
// FIXME Manually trigger this action here, this brings control code to UI = BAD!
setDroneOSHost(m_ui->droneOSComboBox->currentText());
// Update values
m_ui->versionLabel->setText(tr("MAVLINK_VERSION: %1").arg(protocol->getVersion()));
// Connect visibility updates
connect(protocol, &MAVLinkProtocol::versionCheckChanged, m_ui->versionLabel, &QWidget::setVisible);
m_ui->versionLabel->setVisible(protocol->versionCheckEnabled());
// // Multiplexing visibility
// 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());
// Param guard visibility
connect(protocol, &MAVLinkProtocol::paramGuardChanged, m_ui->paramRetransmissionSpinBox, &QWidget::setVisible);
m_ui->paramRetransmissionSpinBox->setVisible(protocol->paramGuardEnabled());
connect(protocol, &MAVLinkProtocol::paramGuardChanged, m_ui->paramRetransmissionLabel, &QWidget::setVisible);
m_ui->paramRetransmissionLabel->setVisible(protocol->paramGuardEnabled());
connect(protocol, &MAVLinkProtocol::paramGuardChanged, m_ui->paramRewriteSpinBox, &QWidget::setVisible);
m_ui->paramRewriteSpinBox->setVisible(protocol->paramGuardEnabled());
connect(protocol, &MAVLinkProtocol::paramGuardChanged, m_ui->paramRewriteLabel, &QWidget::setVisible);
m_ui->paramRewriteLabel->setVisible(protocol->paramGuardEnabled());
// Action guard visibility
connect(protocol, &MAVLinkProtocol::actionGuardChanged, m_ui->actionRetransmissionSpinBox, &QWidget::setVisible);
m_ui->actionRetransmissionSpinBox->setVisible(protocol->actionGuardEnabled());
connect(protocol, &MAVLinkProtocol::actionGuardChanged, m_ui->actionRetransmissionLabel, &QWidget::setVisible);
m_ui->actionRetransmissionLabel->setVisible(protocol->actionGuardEnabled());
// TODO implement filtering
// and then remove these two lines
m_ui->multiplexingFilterCheckBox->setVisible(false);
m_ui->multiplexingFilterLineEdit->setVisible(false);
}
void MAVLinkSettingsWidget::enableDroneOS(bool enable)
{
// Enable multiplexing
protocol->enableMultiplexing(enable);
// Get current selected host and port
QString hostString = m_ui->droneOSComboBox->currentText();
//QString host = hostString.split(":").first();
LinkManager* linkMgr = qgcApp()->toolbox()->linkManager();
UDPLink* firstUdp = NULL;
// Delete from all lists first
for (int i=0; i<linkMgr->links()->count(); i++) {
LinkInterface* link = linkMgr->links()->value<LinkInterface*>(i);
UDPLink* udp = qobject_cast<UDPLink*>(link);
if (udp)
{
if (!firstUdp) firstUdp = udp;
// Remove current hosts
for (int i = 0; i < m_ui->droneOSComboBox->count(); ++i)
{
QString oldHostString = m_ui->droneOSComboBox->itemText(i);
oldHostString = hostString.split(":").first();
udp->removeHost(oldHostString);
}
}
}
// Re-add if enabled
if (enable)
{
if (firstUdp)
{
firstUdp->addHost(hostString);
}
// Set key
protocol->setAuthKey(m_ui->droneOSLineEdit->text().trimmed());
QSettings settings;
settings.setValue("DRONELINK_HOST", m_ui->droneOSComboBox->currentText());
}
protocol->enableAuth(enable);
}
void MAVLinkSettingsWidget::setDroneOSKey(QString key)
{
Q_UNUSED(key);
enableDroneOS(m_ui->droneOSCheckBox->isChecked());
}
void MAVLinkSettingsWidget::setDroneOSHost(QString host)
{
Q_UNUSED(host);
enableDroneOS(m_ui->droneOSCheckBox->isChecked());
}
MAVLinkSettingsWidget::~MAVLinkSettingsWidget()
{
delete m_ui;
}
void MAVLinkSettingsWidget::changeEvent(QEvent *e)
{
QWidget::changeEvent(e);
switch (e->type()) {
case QEvent::LanguageChange:
m_ui->retranslateUi(this);
break;
default:
break;
}
}
void MAVLinkSettingsWidget::hideEvent(QHideEvent* event)
{
Q_UNUSED(event);
protocol->storeSettings();
}
#ifndef MAVLINKSETTINGSWIDGET_H
#define MAVLINKSETTINGSWIDGET_H
#include <QWidget>
#include "MAVLinkProtocol.h"
namespace Ui
{
class MAVLinkSettingsWidget;
}
class MAVLinkSettingsWidget : public QWidget
{
Q_OBJECT
public:
MAVLinkSettingsWidget(MAVLinkProtocol* protocol, QWidget *parent = 0);
~MAVLinkSettingsWidget();
public slots:
/** @brief Enable DroneOS forwarding */
void enableDroneOS(bool enable);
void setDroneOSKey(QString key);
void setDroneOSHost(QString host);
protected:
MAVLinkProtocol* protocol;
void changeEvent(QEvent *e);
void hideEvent(QHideEvent* event);
private:
Ui::MAVLinkSettingsWidget *m_ui;
};
#endif // MAVLINKSETTINGSWIDGET_H
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>MAVLinkSettingsWidget</class>
<widget class="QWidget" name="MAVLinkSettingsWidget">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>431</width>
<height>442</height>
</rect>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QGridLayout" name="gridLayout" columnstretch="1,0,0">
<item row="11" column="0" colspan="3">
<widget class="QCheckBox" name="actionGuardCheckBox">
<property name="text">
<string>Enable retransmission of actions / commands</string>
</property>
</widget>
</item>
<item row="14" column="0" colspan="3">
<widget class="QCheckBox" name="droneOSCheckBox">
<property name="text">
<string>Forward MAVLink packets of all links to the host below</string>
</property>
</widget>
</item>
<item row="6" 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="9" column="1">
<widget class="QLabel" name="paramRetransmissionLabel">
<property name="text">
<string>Read request retransmission timeout</string>
</property>
</widget>
</item>
<item row="8" column="0" colspan="3">
<widget class="QCheckBox" name="paramGuardCheckBox">
<property name="text">
<string>Enable retransmission of parameter read/write requests</string>
</property>
</widget>
</item>
<item row="2" 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>
<item row="4" 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="10" column="0">
<spacer name="horizontalSpacer_2">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="9" column="2">
<widget class="QSpinBox" name="paramRetransmissionSpinBox">
<property name="toolTip">
<string>Time in milliseconds after which a not acknowledged read request is sent again.</string>
</property>
<property name="statusTip">
<string>Time in milliseconds after which a not acknowledged read request is sent again.</string>
</property>
<property name="suffix">
<string> ms</string>
</property>
<property name="minimum">
<number>50</number>
</property>
<property name="maximum">
<number>60000</number>
</property>
<property name="singleStep">
<number>50</number>
</property>
<property name="value">
<number>50</number>
</property>
</widget>
</item>
<item row="15" column="1" colspan="2">
<widget class="QLineEdit" name="droneOSLineEdit">
<property name="text">
<string>Enter your authentication token</string>
</property>
<property name="maxLength">
<number>32</number>
</property>
</widget>
</item>
<item row="9" column="0">
<spacer name="horizontalSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="10" column="2">
<widget class="QSpinBox" name="paramRewriteSpinBox">
<property name="toolTip">
<string>Time in milliseconds after which a not acknowledged write request is sent again.</string>
</property>
<property name="statusTip">
<string>Time in milliseconds after which a not acknowledged write request is sent again.</string>
</property>
<property name="suffix">
<string> ms</string>
</property>
<property name="minimum">
<number>50</number>
</property>
<property name="maximum">
<number>60000</number>
</property>
<property name="singleStep">
<number>50</number>
</property>
</widget>
</item>
<item row="12" column="1">
<widget class="QLabel" name="actionRetransmissionLabel">
<property name="text">
<string>Action request retransmission timeout</string>
</property>
</widget>
</item>
<item row="0" column="0" colspan="2">
<widget class="QLabel" name="systemIdLabel">
<property name="toolTip">
<string>The system ID is the number the MAV associates with this computer</string>
</property>
<property name="statusTip">
<string>The system ID is the number the MAV associates with this computer</string>
</property>
<property name="text">
<string>Groundstation MAVLink System ID</string>
</property>
</widget>
</item>
<item row="7" column="1" colspan="2">
<widget class="QLabel" name="versionLabel">
<property name="text">
<string>MAVLINK_VERSION: </string>
</property>
</widget>
</item>
<item row="0" column="2">
<widget class="QSpinBox" name="systemIdSpinBox">
<property name="toolTip">
<string>Set the groundstation number</string>
</property>
<property name="statusTip">
<string>Set the groundstation number</string>
</property>
<property name="minimum">
<number>1</number>
</property>
<property name="maximum">
<number>255</number>
</property>
</widget>
</item>
<item row="15" column="0">
<spacer name="horizontalSpacer_4">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="13" column="0" colspan="3">
<widget class="Line" name="line">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="midLineWidth">
<number>0</number>
</property>
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
</widget>
</item>
<item row="16" column="1" colspan="2">
<widget class="QComboBox" name="droneOSComboBox">
<property name="editable">
<bool>true</bool>
</property>
<item>
<property name="text">
<string>dronelink.io:14555</string>
</property>
</item>
<item>
<property name="text">
<string>localhost:14555</string>
</property>
</item>
</widget>
</item>
<item row="3" 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="12" column="0">
<spacer name="horizontalSpacer_3">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</item>
<item row="4" 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="10" column="1">
<widget class="QLabel" name="paramRewriteLabel">
<property name="text">
<string>Write request retransmission timeout</string>
</property>
</widget>
</item>
<item row="12" column="2">
<widget class="QSpinBox" name="actionRetransmissionSpinBox">
<property name="suffix">
<string> ms</string>
</property>
<property name="minimum">
<number>20</number>
</property>
<property name="maximum">
<number>1000</number>
</property>
<property name="singleStep">
<number>10</number>
</property>
</widget>
</item>
<item row="7" column="0">
<spacer name="versionSpacer">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>8</width>
<height>0</height>
</size>
</property>
</spacer>
</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