From 79948c12c4fcadeadc5551f523351aa00c015273 Mon Sep 17 00:00:00 2001 From: lm Date: Fri, 22 Apr 2011 17:05:09 +0200 Subject: [PATCH] Working on 2D map --- src/comm/UDPLink.cc | 15 +++++++++++---- src/ui/QGCMapWidget.cc | 14 +++++++++++++- 2 files changed, 24 insertions(+), 5 deletions(-) diff --git a/src/comm/UDPLink.cc b/src/comm/UDPLink.cc index 2a73334..56fa9f8 100644 --- a/src/comm/UDPLink.cc +++ b/src/comm/UDPLink.cc @@ -143,7 +143,6 @@ void UDPLink::removeHost(const QString& hostname) } } - void UDPLink::writeBytes(const char* data, qint64 size) { // Broadcast to all connected systems @@ -151,18 +150,26 @@ void UDPLink::writeBytes(const char* data, qint64 size) { QHostAddress currentHost = hosts.at(h); quint16 currentPort = ports.at(h); +//#define UDPLINK_DEBUG +#ifdef UDPLINK_DEBUG QString bytes; QString ascii; - //qDebug() << "WRITING DATA TO" << currentHost.toString() << currentPort; for (int i=0; i 31 && data[i] < 127) + { + ascii.append(data[i]); + } + else + { + ascii.append(219); + } } qDebug() << "Sent" << size << "bytes to" << currentHost.toString() << ":" << currentPort << "data:"; qDebug() << bytes; qDebug() << "ASCII:" << ascii; - +#endif socket->writeDatagram(data, size, currentHost, currentPort); } } diff --git a/src/ui/QGCMapWidget.cc b/src/ui/QGCMapWidget.cc index 711ec9e..82ab2a6 100644 --- a/src/ui/QGCMapWidget.cc +++ b/src/ui/QGCMapWidget.cc @@ -1,9 +1,19 @@ #include "QGCMapWidget.h" #include "UASInterface.h" +#include "UASManager.h" QGCMapWidget::QGCMapWidget(QWidget *parent) : mapcontrol::OPMapWidget(parent) { + //UAV = new mapcontrol::UAVItem(); + connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*))); + foreach (UASInterface* uas, UASManager::instance()->getUASList()) + { + addUAS(uas); + } + UAV->setVisible(true); + UAV->setPos(40, 8); + UAV->show(); } /** @@ -31,7 +41,9 @@ void QGCMapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lo Q_UNUSED(usec); Q_UNUSED(alt); // FIXME Use altitude - + UAV->setPos(lat, lon); + UAV->show(); + qDebug() << "Updating 2D map position"; // QPointF coordinate; // coordinate.setX(lon);