diff --git a/lib/QMapControl/src/imagemanager.cpp b/lib/QMapControl/src/imagemanager.cpp index e410ad6e02de11bcf69312a1f6f6341d0e655e36..d681753b1c3d024e036b0217e32d4225c5d6f791 100644 --- a/lib/QMapControl/src/imagemanager.cpp +++ b/lib/QMapControl/src/imagemanager.cpp @@ -153,7 +153,7 @@ namespace qmapcontrol QBuffer buffer(&bytes); buffer.open(QIODevice::WriteOnly); tileData.save(&buffer, "PNG"); - + // FIXME This is weird - why first write in buffer and then in file? file.write(bytes); file.close(); return true; diff --git a/lib/QMapControl/src/layer.cpp b/lib/QMapControl/src/layer.cpp index 62d78f1de186ce76c5d23c3a73911a5f3863cf1b..dddd4c3d3b1b4bbdae2aa51ce415ea4acc360d75 100644 --- a/lib/QMapControl/src/layer.cpp +++ b/lib/QMapControl/src/layer.cpp @@ -39,10 +39,10 @@ namespace qmapcontrol delete mapAdapter; } - void Layer::setSize(QSize size) + void Layer::setSize(QSize size, QPoint screenmiddle) { this->size = size; - screenmiddle = QPoint(size.width()/2, size.height()/2); + this->screenmiddle = screenmiddle;// QPoint(size.width()/2, size.height()/2); //QMatrix mat; //mat.translate(480/2, 640/2); //mat.rotate(45); @@ -292,10 +292,12 @@ namespace qmapcontrol // PREFETCHING - int upper = mapmiddle_tile_y-tiles_above-1; - int right = mapmiddle_tile_x+tiles_right+1; - int left = mapmiddle_tile_x-tiles_right-1; - int lower = mapmiddle_tile_y+tiles_bottom+1; + + // FIXME Make prefetching a parameter + int upper = mapmiddle_tile_y-tiles_above-2; + int right = mapmiddle_tile_x+tiles_right+2; + int left = mapmiddle_tile_x-tiles_right-2; + int lower = mapmiddle_tile_y+tiles_bottom+2; int j = upper; for (int i=left; i<=right; i++) diff --git a/lib/QMapControl/src/layer.h b/lib/QMapControl/src/layer.h index 46fd5b19ed28d65eda18863204c2c0edfa9ba339..48db8b4aa1f80291529ba2047a7e614d7babb3e9 100644 --- a/lib/QMapControl/src/layer.h +++ b/lib/QMapControl/src/layer.h @@ -139,7 +139,7 @@ namespace qmapcontrol void moveWidgets(const QPoint mapmiddle_px) const; void drawYourImage(QPainter* painter, const QPoint mapmiddle_px) const; void drawYourGeometries(QPainter* painter, const QPoint mapmiddle_px, QRect viewport) const; - void setSize(QSize size); + void setSize(QSize size, QPoint screenmiddle); QRect offscreenViewport() const; bool takesMouseEvents() const; void mouseEvent(const QMouseEvent*, const QPoint mapmiddle_px); diff --git a/lib/QMapControl/src/layermanager.cpp b/lib/QMapControl/src/layermanager.cpp index 3bc827d5c86531474dc0e47da43939b2a985e933..7721e7448e4274932e9f9a050ead67ccfbd55c36 100644 --- a/lib/QMapControl/src/layermanager.cpp +++ b/lib/QMapControl/src/layermanager.cpp @@ -47,6 +47,7 @@ namespace qmapcontrol offFactor = factor; composedOffscreenImage = QPixmap(offSize); composedOffscreenImage2 = QPixmap(offSize); + resize(size); } float LayerManager::offscreenImageFactor() @@ -219,7 +220,7 @@ namespace qmapcontrol { mylayers.append(layer); - layer->setSize(size); + layer->setSize(size, screenmiddle); connect(layer, SIGNAL(updateRequest(QRectF)), this, SLOT(updateRequest(QRectF))); @@ -493,7 +494,7 @@ namespace qmapcontrol while (it.hasNext()) { Layer* l = it.next(); - l->setSize(newSize); + l->setSize(newSize, screenmiddle); } newOffscreenImage(); diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index c2cf73b94c9f5ac82a391f8cebdea6beb7c1d3fa..affe46b7fc913c26fdf2dc78ba0cdd73d1d669ee 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -66,10 +66,13 @@ LinkManager::~LinkManager() void LinkManager::add(LinkInterface* link) { - if(!link) return; - connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*))); - links.append(link); - emit newLink(link); + if (!links.contains(link)) + { + if(!link) return; + connect(link, SIGNAL(destroyed(QObject*)), this, SLOT(removeLink(QObject*))); + links.append(link); + emit newLink(link); + } } void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol) @@ -77,9 +80,18 @@ void LinkManager::addProtocol(LinkInterface* link, ProtocolInterface* protocol) // Connect link to protocol // the protocol will receive new bytes from the link if(!link || !protocol) return; - connect(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)), protocol, SLOT(receiveBytes(LinkInterface*, QByteArray))); - // Store the connection information in the protocol links map - protocolLinks.insertMulti(protocol, link); + + QList linkList = protocolLinks.values(protocol); + + // If protocol has not been added before (list length == 0) + // OR if link has not been added to protocol, add + if ((linkList.length() > 0 && !linkList.contains(link)) || linkList.length() == 0) + { + // Protocol is new, add + connect(link, SIGNAL(bytesReceived(LinkInterface*, QByteArray)), protocol, SLOT(receiveBytes(LinkInterface*, QByteArray))); + // Store the connection information in the protocol links map + protocolLinks.insertMulti(protocol, link); + } //qDebug() << __FILE__ << __LINE__ << "ADDED LINK TO PROTOCOL" << link->getName() << protocol->getName() << "NEW SIZE OF LINK LIST:" << protocolLinks.size(); } diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 7adc9364d8f41f9a23ca67121d4bdcdc1c37c534..c4e86e77d137e1abee1c4bd9e814933b465b640e 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -154,7 +154,7 @@ void MAVLinkSimulationLink::sendMAVLinkMessage(const mavlink_message_t* msg) // Pack to link buffer readyBufferMutex.lock(); - for (int i = 0; i < bufferlength; i++) + for (unsigned int i = 0; i < bufferlength; i++) { readyBuffer.enqueue(*(buf + i)); } @@ -954,6 +954,7 @@ bool MAVLinkSimulationLink::connect() start(LowPriority); MAVLinkSimulationMAV* mav1 = new MAVLinkSimulationMAV(this, 1); + Q_UNUSED(mav1); // timer->start(rate); return true; } diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 7f9f50d5ff49002280b1b27190ef046d7a6f7e17..8d857dd0f0a50e3d68d49e6f04c42cba4f9c8e6f 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -87,9 +87,6 @@ SerialLink::SerialLink(QString portname, BaudRateType baudrate, FlowType flow, P #endif loadSettings(); - - // Link is setup, register it with link manager - LinkManager::instance()->add(this); } SerialLink::~SerialLink() diff --git a/src/ui/CommConfigurationWindow.cc b/src/ui/CommConfigurationWindow.cc index 484290d99a2dcecbcee944bc69c35bc3d3c5e863..15a66edd51406c98b14d4af2d71e97b546568ddf 100644 --- a/src/ui/CommConfigurationWindow.cc +++ b/src/ui/CommConfigurationWindow.cc @@ -68,6 +68,8 @@ CommConfigurationWindow::CommConfigurationWindow(LinkInterface* link, ProtocolIn // Create configuration action for this link // Connect the current UAS action = new QAction(QIcon(":/images/devices/network-wireless.svg"), "", link); + LinkManager::instance()->add(link); + action->setData(LinkManager::instance()->getLinks().indexOf(link)); setLinkName(link->getName()); connect(action, SIGNAL(triggered()), this, SLOT(show())); @@ -209,11 +211,12 @@ void CommConfigurationWindow::remove() link->disconnect(); //disconnect port, and also calls terminate() to stop the thread if (link->isRunning()) link->terminate(); // terminate() the serial thread just in case it is still running link->wait(); // wait() until thread is stoped before deleting - delete link; + link->deleteLater(); } link=NULL; this->window()->close(); + this->deleteLater(); } void CommConfigurationWindow::connectionState(bool connect) diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 363e2f4503ddfeb0a1c3708e8fd84ffcb6798cd9..74b9f660bcc3e68cb9358ce9f65a0ac24acf8140 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -1205,18 +1205,27 @@ void MainWindow::addLink() SerialLink* link = new SerialLink(); // TODO This should be only done in the dialog itself + LinkManager::instance()->add(link); LinkManager::instance()->addProtocol(link, mavlink); - CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this); - - ui.menuNetwork->addAction(commWidget->getAction()); + // Go fishing for this link's configuration window + QList actions = ui.menuNetwork->actions(); - commWidget->show(); + foreach (QAction* act, actions) + { + if (act->data().toInt() == LinkManager::instance()->getLinks().indexOf(link)) + { + act->trigger(); + break; + } + } } void MainWindow::addLink(LinkInterface *link) { + LinkManager::instance()->add(link); LinkManager::instance()->addProtocol(link, mavlink); + CommConfigurationWindow* commWidget = new CommConfigurationWindow(link, mavlink, this); ui.menuNetwork->addAction(commWidget->getAction()); diff --git a/src/ui/MapWidget.cc b/src/ui/MapWidget.cc index a291ed9958d502446f328578ed96af5219da5988..e2a95a1043576057ac5fef607f6e186b0d1d5792 100644 --- a/src/ui/MapWidget.cc +++ b/src/ui/MapWidget.cc @@ -42,14 +42,6 @@ MapWidget::MapWidget(QWidget *parent) : QString buttonStyle("QAbstractButton { background-color: rgba(20, 20, 20, 45%); border-color: rgba(10, 10, 10, 50%)} QDoubleSpinBox { background-color: rgba(20, 20, 20, 45%); border-color: rgba(10, 10, 10, 50%)}"); mc->setPen(QGC::colorCyan.darker(400)); - - - - - - - - waypointIsDrag = false; // Accept focus by clicking or keyboard @@ -267,6 +259,10 @@ MapWidget::MapWidget(QWidget *parent) : drawCamBorder = false; radioCamera = 10; +// mc->setZoom(20); +// //mc->resize(QSize(7025, 4968)); +// mc->resize(QSize(3000, 2000)); + //mc->setOffscreenImageFactor(15); } diff --git a/src/ui/SerialConfigurationWindow.cc b/src/ui/SerialConfigurationWindow.cc index f7305bc37b03c82617aa7380ba0cd9396de9f0b4..c5738edb65efbb9e7677166af3a6c908d1a4d4cf 100644 --- a/src/ui/SerialConfigurationWindow.cc +++ b/src/ui/SerialConfigurationWindow.cc @@ -320,7 +320,8 @@ userConfigured(false) } } -SerialConfigurationWindow::~SerialConfigurationWindow() { +SerialConfigurationWindow::~SerialConfigurationWindow() +{ }