diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index 4ebf8fb604e453d252a40d61beccdf4a0f63eb35..2462df8d6eebf97d5d660b3da3c1bd8a692ce90c 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -368,6 +368,7 @@ void UDPConfiguration::copyFrom(LinkConfiguration *source) UDPConfiguration* usource = dynamic_cast(source); Q_ASSERT(usource != NULL); _localPort = usource->localPort(); + _hosts.clear(); QString host; int port; if(usource->firstHost(host, port)) { @@ -407,7 +408,7 @@ void UDPConfiguration::addHost(const QString& host, int port) qWarning() << "UDP:" << "Could not resolve host:" << host << "port:" << port; } else { _hosts[ipAdd] = port; - qDebug() << "UDP:" << "Adding Host:" << ipAdd << ":" << port; + //qDebug() << "UDP:" << "Adding Host:" << ipAdd << ":" << port; } } } diff --git a/src/ui/QGCUDPLinkConfiguration.cc b/src/ui/QGCUDPLinkConfiguration.cc index 584257fd980096d9bd27a679c8b11fdbf498051f..f1fcef6cfcf1c209b34d1493edc055b1e2d44a5f 100644 --- a/src/ui/QGCUDPLinkConfiguration.cc +++ b/src/ui/QGCUDPLinkConfiguration.cc @@ -72,13 +72,16 @@ void QGCUDPLinkConfiguration::_editHost(int row) { if(row < _viewModel->hosts.count()) { bool ok; + QString oldName = _viewModel->hosts.at(row); QString hostName = QInputDialog::getText( this, tr("Edit a MAVLink host target"), - tr("Host (hostname:port): "), QLineEdit::Normal, _viewModel->hosts.at(row), &ok); + tr("Host (hostname:port): "), QLineEdit::Normal, oldName, &ok); if (ok && !hostName.isEmpty()) { _viewModel->beginChange(); _viewModel->hosts.replace(row, hostName); _viewModel->endChange(); + _config->removeHost(oldName); + _config->addHost(hostName); } } } @@ -119,7 +122,9 @@ void QGCUDPLinkConfiguration::on_removeHost_clicked() { QModelIndex index = _ui->listView->currentIndex(); if(index.row() < _viewModel->hosts.count()) { + QString oldName = _viewModel->hosts.at(index.row()); _viewModel->hosts.removeAt(index.row()); + _config->removeHost(oldName); _reloadList(); } }