QGCUDPLinkConfiguration.cc 4.35 KB
Newer Older
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29
/*=====================================================================

QGroundControl Open Source Ground Control Station

(c) 2009, 2010 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>

This file is part of the QGROUNDCONTROL project

    QGROUNDCONTROL is free software: you can redistribute it and/or modify
    it under the terms of the GNU General Public License as published by
    the Free Software Foundation, either version 3 of the License, or
    (at your option) any later version.

    QGROUNDCONTROL is distributed in the hope that it will be useful,
    but WITHOUT ANY WARRANTY; without even the implied warranty of
    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
    GNU General Public License for more details.

    You should have received a copy of the GNU General Public License
    along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.

======================================================================*/

/**
 * @file
 *   @brief Implementation of QGCUDPLinkConfiguration
 *   @author Gus Grubba <mavlink@grubba.com>
 */

30 31 32 33 34
#include <QInputDialog>

#include "QGCUDPLinkConfiguration.h"
#include "ui_QGCUDPLinkConfiguration.h"

35 36 37 38
QGCUDPLinkConfiguration::QGCUDPLinkConfiguration(UDPConfiguration *config, QWidget *parent)
    : QWidget(parent)
    , _inConstructor(true)
    , _ui(new Ui::QGCUDPLinkConfiguration)
39
{
40 41 42 43 44 45 46 47 48 49
    _config = config;
    _ui->setupUi(this);
    _viewModel = new UPDViewModel;
    _ui->listView->setModel(_viewModel);
    _ui->removeHost->setEnabled(false);
    _ui->editHost->setEnabled(false);
    _ui->portNumber->setRange(1024, 65535);
    _ui->portNumber->setValue(_config->localPort());
    _reloadList();
    _inConstructor = false;
50 51 52 53
}

QGCUDPLinkConfiguration::~QGCUDPLinkConfiguration()
{
54
    delete _ui;
55 56
}

57
void QGCUDPLinkConfiguration::_reloadList()
58
{
59 60 61 62 63 64 65 66 67
    QString host;
    int port;
    if(_config->firstHost(host, port)) {
        _viewModel->beginChange();
        _viewModel->hosts.clear();
        do {
            _viewModel->hosts.append(QString("%1:%2").arg(host, QString::number(port)));
        } while (_config->nextHost(host, port));
        _viewModel->endChange();
68 69 70
    }
}

71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105
void QGCUDPLinkConfiguration::_editHost(int row)
{
    if(row < _viewModel->hosts.count()) {
        bool ok;
        QString hostName = QInputDialog::getText(
            this, tr("Edit a MAVLink host target"),
            tr("Host (hostname:port):                                                     "), QLineEdit::Normal, _viewModel->hosts.at(row), &ok);
        if (ok && !hostName.isEmpty()) {
            _viewModel->beginChange();
            _viewModel->hosts.replace(row, hostName);
            _viewModel->endChange();
        }
    }
}

void QGCUDPLinkConfiguration::on_portNumber_valueChanged(int arg1)
{
    if(!_inConstructor) {
        _config->setLocalPort(arg1);
    }
}

void QGCUDPLinkConfiguration::on_listView_clicked(const QModelIndex &index)
{
    bool enabled = index.row() < _viewModel->hosts.count();
    _ui->removeHost->setEnabled(enabled);
    _ui->editHost->setEnabled(enabled);
}

void QGCUDPLinkConfiguration::on_listView_doubleClicked(const QModelIndex &index)
{
    _editHost(index.row());
}

void QGCUDPLinkConfiguration::on_addHost_clicked()
106 107
{
    bool ok;
108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150
    QString hostName = QInputDialog::getText(
        this, tr("Add a host target to MAVLink"),
        tr("Host (hostname:port):                                                     "),
        QLineEdit::Normal, QString("localhost:%1").arg(QGC_UDP_PORT), &ok);
    if (ok && !hostName.isEmpty()) {
        _config->addHost(hostName);
        _reloadList();
    }
}

void QGCUDPLinkConfiguration::on_removeHost_clicked()
{
    QModelIndex index = _ui->listView->currentIndex();
    if(index.row() < _viewModel->hosts.count()) {
        _viewModel->hosts.removeAt(index.row());
        _reloadList();
    }
}

void QGCUDPLinkConfiguration::on_editHost_clicked()
{
    QModelIndex index = _ui->listView->currentIndex();
    _editHost(index.row());
}


UPDViewModel::UPDViewModel(QObject *parent) : QAbstractListModel(parent)
{
    Q_UNUSED(parent);
}

int UPDViewModel::rowCount( const QModelIndex & parent) const
{
    Q_UNUSED(parent);
    return hosts.count();
}

QVariant UPDViewModel::data( const QModelIndex & index, int role) const
{
    if (role == Qt::DisplayRole && index.row() < hosts.count()) {
        return hosts.at(index.row());
    }
    return QVariant();
151
}