From 32e1c5297162da947a76f255e441c1acd5dde45e Mon Sep 17 00:00:00 2001 From: pixhawk Date: Sat, 1 Jan 2011 16:46:09 +0100 Subject: [PATCH] Fixed QMapControl bug --- lib/QMapControl/src/layermanager.cpp | 10 +- src/comm/LinkInterface.h | 1 + src/comm/MAVLinkSimulationLink.cc | 3 +- src/comm/MAVLinkSimulationLink.h | 2 +- src/comm/MAVLinkSwarmSimulationLink.cc | 4 +- src/comm/MAVLinkSwarmSimulationLink.h | 2 +- src/uas/UASManager.cc | 12 +- src/ui/MapWidget.cc | 298 +++++++++--------- .../AirfoilServoCalibrator.cc | 6 +- .../RadioCalibration/RadioCalibrationData.cc | 3 + .../RadioCalibrationWindow.cc | 3 + src/ui/SlugsHilSim.cc | 10 +- src/ui/WaypointList.cc | 4 +- src/ui/map3D/QGCGoogleEarthView.cc | 6 +- src/ui/map3D/QOSGWidget.cc | 6 +- 15 files changed, 194 insertions(+), 176 deletions(-) diff --git a/lib/QMapControl/src/layermanager.cpp b/lib/QMapControl/src/layermanager.cpp index 3e10bb225..3358605a4 100644 --- a/lib/QMapControl/src/layermanager.cpp +++ b/lib/QMapControl/src/layermanager.cpp @@ -112,7 +112,14 @@ namespace qmapcontrol void LayerManager::setView(const QPointF& coordinate) { + QPoint oldMapPx = mapmiddle_px; + mapmiddle_px = layer()->mapadapter()->coordinateToDisplay(coordinate); + + scroll += mapmiddle_px - oldMapPx; + zoomImageScroll+= mapmiddle_px - oldMapPx; + + mapmiddle = coordinate; //TODO: muss wegen moveTo() raus @@ -125,7 +132,8 @@ namespace qmapcontrol //TODO: // verschiebung ausrechnen // oder immer neues offscreenimage - newOffscreenImage(); + //newOffscreenImage(); + moveWidgets(); } } diff --git a/src/comm/LinkInterface.h b/src/comm/LinkInterface.h index b632b26ba..21efec7a0 100644 --- a/src/comm/LinkInterface.h +++ b/src/comm/LinkInterface.h @@ -42,6 +42,7 @@ along with PIXHAWK. If not, see . class LinkInterface : public QThread { Q_OBJECT public: + LinkInterface(QObject* parent = 0) : QThread(parent) {} //virtual ~LinkInterface() = 0; /* Connection management */ diff --git a/src/comm/MAVLinkSimulationLink.cc b/src/comm/MAVLinkSimulationLink.cc index 507b20b02..a4606b528 100644 --- a/src/comm/MAVLinkSimulationLink.cc +++ b/src/comm/MAVLinkSimulationLink.cc @@ -55,7 +55,7 @@ This file is part of the QGROUNDCONTROL project * @param writeFile The received messages are written to that file * @param rate The rate at which the messages are sent (in intervals of milliseconds) **/ -MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile, int rate) : +MAVLinkSimulationLink::MAVLinkSimulationLink(QString readFile, QString writeFile, int rate, QObject* parent) : LinkInterface(parent), readyBytes(0), timeOffset(0) { @@ -445,6 +445,7 @@ void MAVLinkSimulationLink::mainloop() chan.chan6_raw = (chan.chan3_raw + chan.chan2_raw) / 2.0f; chan.chan7_raw = (chan.chan4_raw + chan.chan2_raw) / 2.0f; chan.chan8_raw = (chan.chan6_raw + chan.chan2_raw) / 2.0f; + chan.rssi = 100; messageSize = mavlink_msg_rc_channels_raw_encode(systemId, componentId, &msg, &chan); // Allocate buffer with packet data bufferlength = mavlink_msg_to_send_buffer(buffer, &msg); diff --git a/src/comm/MAVLinkSimulationLink.h b/src/comm/MAVLinkSimulationLink.h index 5940d1aeb..383cb71aa 100644 --- a/src/comm/MAVLinkSimulationLink.h +++ b/src/comm/MAVLinkSimulationLink.h @@ -47,7 +47,7 @@ class MAVLinkSimulationLink : public LinkInterface { Q_OBJECT public: - MAVLinkSimulationLink(QString readFile="", QString writeFile="", int rate=5); + MAVLinkSimulationLink(QString readFile="", QString writeFile="", int rate=5, QObject* parent = 0); ~MAVLinkSimulationLink(); bool isConnected(); qint64 bytesAvailable(); diff --git a/src/comm/MAVLinkSwarmSimulationLink.cc b/src/comm/MAVLinkSwarmSimulationLink.cc index c94c52896..a3ec913d9 100644 --- a/src/comm/MAVLinkSwarmSimulationLink.cc +++ b/src/comm/MAVLinkSwarmSimulationLink.cc @@ -1,7 +1,7 @@ #include "MAVLinkSwarmSimulationLink.h" -MAVLinkSwarmSimulationLink::MAVLinkSwarmSimulationLink(QObject *parent) : - MAVLinkSimulationLink() +MAVLinkSwarmSimulationLink::MAVLinkSwarmSimulationLink(QString readFile, QString writeFile, int rate, QObject *parent) : + MAVLinkSimulationLink(readFile, writeFile, rate, parent) { } diff --git a/src/comm/MAVLinkSwarmSimulationLink.h b/src/comm/MAVLinkSwarmSimulationLink.h index d4b4996d0..8a35c43e1 100644 --- a/src/comm/MAVLinkSwarmSimulationLink.h +++ b/src/comm/MAVLinkSwarmSimulationLink.h @@ -7,7 +7,7 @@ class MAVLinkSwarmSimulationLink : public MAVLinkSimulationLink { Q_OBJECT public: - explicit MAVLinkSwarmSimulationLink(QObject *parent = 0); + MAVLinkSwarmSimulationLink(QString readFile="", QString writeFile="", int rate=5, QObject *parent = 0); signals: diff --git a/src/uas/UASManager.cc b/src/uas/UASManager.cc index cb3183cb9..37f02e79c 100644 --- a/src/uas/UASManager.cc +++ b/src/uas/UASManager.cc @@ -104,12 +104,12 @@ QList UASManager::getUASList() UASInterface* UASManager::getActiveUAS() { - if(!activeUAS) - { - QMessageBox msgBox; - msgBox.setText(tr("No Micro Air Vehicle connected. Please connect one first.")); - msgBox.exec(); - } +// if(!activeUAS) +// { +// QMessageBox msgBox; +// msgBox.setText(tr("No Micro Air Vehicle connected. Please connect one first.")); +// msgBox.exec(); +// } return activeUAS; ///< Return zero pointer if no UAS has been loaded } diff --git a/src/ui/MapWidget.cc b/src/ui/MapWidget.cc index 844474049..07e4904bb 100644 --- a/src/ui/MapWidget.cc +++ b/src/ui/MapWidget.cc @@ -1,23 +1,4 @@ /*================================================================== -QGroundControl Open Source Ground Control Station - -(c) 2009, 2010 QGROUNDCONTROL PROJECT - -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 . - ======================================================================*/ /** @@ -52,54 +33,54 @@ MapWidget::MapWidget(QWidget *parent) : m_ui(new Ui::MapWidget) { m_ui->setupUi(this); - + waypointIsDrag = false; - + // Accept focus by clicking or keyboard this->setFocusPolicy(Qt::StrongFocus); - + // create MapControl mc = new qmapcontrol::MapControl(QSize(320, 240)); mc->showScale(true); mc->showCoord(true); - mc->enablePersistentCache(); + mc->enablePersistentCache(qApp->applicationDirPath()); mc->setMouseTracking(true); // required to update the mouse position for diplay and capture - + // create MapAdapter to get maps from //TileMapAdapter* osmAdapter = new TileMapAdapter("tile.openstreetmap.org", "/%1/%2/%3.png", 256, 0, 17); - + qmapcontrol::MapAdapter* mapadapter_overlay = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=2.2&t=h&s=256&x=%2&y=%3&z=%1"); - + // MAP BACKGROUND mapadapter = new qmapcontrol::GoogleSatMapAdapter(); l = new qmapcontrol::MapLayer("Google Satellite", mapadapter); mc->addLayer(l); - + // STREET OVERLAY overlay = new qmapcontrol::MapLayer("Overlay", mapadapter_overlay); overlay->setVisible(false); mc->addLayer(overlay); - + // WAYPOINT LAYER // create a layer with the mapadapter and type GeometryLayer (for waypoints) geomLayer = new qmapcontrol::GeometryLayer("Waypoints", mapadapter); mc->addLayer(geomLayer); - - - + + + // // Layer* gsatLayer = new Layer("Google Satellite", gsat, Layer::MapLayer); // mc->addLayer(gsatLayer); - + // SET INITIAL POSITION AND ZOOM // Set default zoom level mc->setZoom(16); // Zurich, ETH //mc->setView(QPointF(8.548056,47.376389)); - + // Veracruz Mexico, ETH mc->setView(QPointF(-96.105208,19.138955)); - + // Add controls to select map provider ///////////////////////////////////////////////// QActionGroup* mapproviderGroup = new QActionGroup(this); @@ -116,31 +97,31 @@ MapWidget::MapWidget(QWidget *parent) : googleSatAction->setChecked(true); connect(mapproviderGroup, SIGNAL(triggered(QAction*)), this, SLOT(mapproviderSelected(QAction*))); - + // Overlay seems currently broken // yahooActionOverlay = new QAction(tr("Yahoo: street overlay"), this); // yahooActionOverlay->setCheckable(true); // yahooActionOverlay->setChecked(overlay->isVisible()); // connect(yahooActionOverlay, SIGNAL(toggled(bool)), // overlay, SLOT(setVisible(bool))); - + // mapproviderGroup->addAction(googleSatAction); // mapproviderGroup->addAction(osmAction); // mapproviderGroup->addAction(yahooActionOverlay); // mapproviderGroup->addAction(googleActionMap); // mapproviderGroup->addAction(yahooActionMap); // mapproviderGroup->addAction(yahooActionSatellite); - + // Create map provider selection menu mapMenu = new QMenu(this); mapMenu->addActions(mapproviderGroup->actions()); mapMenu->addSeparator(); // mapMenu->addAction(yahooActionOverlay); - + mapButton = new QPushButton(this); mapButton->setText("Map Source"); mapButton->setMenu(mapMenu); - + // display the MapControl in the application QGridLayout* layout = new QGridLayout(this); layout->setMargin(0); @@ -153,24 +134,24 @@ MapWidget::MapWidget(QWidget *parent) : layout->setColumnStretch(0, 1); layout->setColumnStretch(1, 50); setLayout(layout); - + // create buttons to control the map (zoom, GPS tracking and WP capture) QPushButton* zoomin = new QPushButton(QIcon(":/images/actions/list-add.svg"), "", this); QPushButton* zoomout = new QPushButton(QIcon(":/images/actions/list-remove.svg"), "", this); createPath = new QPushButton(QIcon(":/images/actions/go-bottom.svg"), "", this); followgps = new QPushButton(QIcon(":/images/actions/system-lock-screen.svg"), "", this); - + zoomin->setMaximumWidth(50); zoomout->setMaximumWidth(50); createPath->setMaximumWidth(50); followgps->setMaximumWidth(50); - + // Set checkable buttons // TODO: Currently checked buttons are are very difficult to distinguish when checked. // create a style and the slots to change the background so it is easier to distinguish followgps->setCheckable(true); createPath->setCheckable(true); - + // add buttons to control the map (zoom, GPS tracking and WP capture) QGridLayout* innerlayout = new QGridLayout(mc); innerlayout->setMargin(5); @@ -185,56 +166,60 @@ MapWidget::MapWidget(QWidget *parent) : innerlayout->setRowStretch(0, 1); innerlayout->setRowStretch(1, 100); mc->setLayout(innerlayout); - - + + // Connect the required signals-slots connect(zoomin, SIGNAL(clicked(bool)), mc, SLOT(zoomIn())); - + connect(zoomout, SIGNAL(clicked(bool)), mc, SLOT(zoomOut())); - + + QList systems = UASManager::instance()->getUASList(); + foreach(UASInterface* system, systems) + { + addUAS(system); + } + connect(UASManager::instance(), SIGNAL(UASCreated(UASInterface*)), this, SLOT(addUAS(UASInterface*))); + + activeUASSet(UASManager::instance()->getActiveUAS()); connect(UASManager::instance(), SIGNAL(activeUASSet(UASInterface*)), this, SLOT(activeUASSet(UASInterface*))); - + connect(mc, SIGNAL(mouseEventCoordinate(const QMouseEvent*, const QPointF)), this, SLOT(captureMapClick(const QMouseEvent*, const QPointF))); - + connect(createPath, SIGNAL(clicked(bool)), this, SLOT(createPathButtonClicked(bool))); - - + + connect(geomLayer, SIGNAL(geometryClicked(Geometry*,QPoint)), this, SLOT(captureGeometryClick(Geometry*, QPoint))); - + connect(geomLayer, SIGNAL(geometryDragged(Geometry*, QPointF)), this, SLOT(captureGeometryDrag(Geometry*, QPointF))); - + connect(geomLayer, SIGNAL(geometryEndDrag(Geometry*, QPointF)), this, SLOT(captureGeometryEndDrag(Geometry*, QPointF))); - + // Configure the WP Path's pen pointPen = new QPen(QColor(0, 255,0)); pointPen->setWidth(3); - + path = new qmapcontrol::LineString (wps, "UAV Path", pointPen); mc->layer("Waypoints")->addGeometry(path); - + //Camera Control // CAMERA INDICATOR LAYER // create a layer with the mapadapter and type GeometryLayer (for camera indicator) camLayer = new qmapcontrol::GeometryLayer("Camera", mapadapter); mc->addLayer(camLayer); - + //camLine = new qmapcontrol::LineString(camPoints,"Camera Eje", camBorderPen); - + drawCamBorder = false; radioCamera = 10; - - - - this->setVisible(false); } @@ -246,27 +231,27 @@ void MapWidget::mapproviderSelected(QAction* action) { int zoom = mapadapter->adaptedZoom(); mc->setZoom(0); - + mapadapter = new qmapcontrol::OSMMapAdapter(); l->setMapAdapter(mapadapter); geomLayer->setMapAdapter(mapadapter); - + mc->updateRequestNew(); mc->setZoom(zoom); // yahooActionOverlay->setEnabled(false); overlay->setVisible(false); // yahooActionOverlay->setChecked(false); - + } else if (action == yahooActionMap) { int zoom = mapadapter->adaptedZoom(); mc->setZoom(0); - + mapadapter = new qmapcontrol::YahooMapAdapter(); l->setMapAdapter(mapadapter); geomLayer->setMapAdapter(mapadapter); - + mc->updateRequestNew(); mc->setZoom(zoom); // yahooActionOverlay->setEnabled(false); @@ -278,10 +263,10 @@ void MapWidget::mapproviderSelected(QAction* action) int zoom = mapadapter->adaptedZoom(); QPointF a = mc->currentCoordinate(); mc->setZoom(0); - + mapadapter = new qmapcontrol::YahooMapAdapter("us.maps3.yimg.com", "/aerial.maps.yimg.com/png?v=1.7&t=a&s=256&x=%2&y=%3&z=%1"); l->setMapAdapter(mapadapter); - + mc->updateRequestNew(); mc->setZoom(zoom); // yahooActionOverlay->setEnabled(true); @@ -293,7 +278,7 @@ void MapWidget::mapproviderSelected(QAction* action) mapadapter = new qmapcontrol::GoogleMapAdapter(); l->setMapAdapter(mapadapter); geomLayer->setMapAdapter(mapadapter); - + mc->updateRequestNew(); mc->setZoom(zoom); // yahooActionOverlay->setEnabled(false); @@ -307,7 +292,7 @@ void MapWidget::mapproviderSelected(QAction* action) mapadapter = new qmapcontrol::GoogleSatMapAdapter(); l->setMapAdapter(mapadapter); geomLayer->setMapAdapter(mapadapter); - + mc->updateRequestNew(); mc->setZoom(zoom); // yahooActionOverlay->setEnabled(false); @@ -324,19 +309,19 @@ void MapWidget::mapproviderSelected(QAction* action) void MapWidget::createPathButtonClicked(bool checked) { Q_UNUSED(checked); - - - + + + if (createPath->isChecked()) { // change the cursor shape this->setCursor(Qt::PointingHandCursor); mc->setMouseMode(qmapcontrol::MapControl::None); - - + + // emit signal start to create a Waypoint global emit createGlobalWP(true, mc->currentCoordinate()); - + // // Clear the previous WP track // // TODO: Move this to an actual clear track button and add a warning dialog // mc->layer("Waypoints")->clearGeometries(); @@ -344,16 +329,16 @@ void MapWidget::createPathButtonClicked(bool checked) // path->setPoints(wps); // mc->layer("Waypoints")->addGeometry(path); // wpIndex.clear(); - - + + } else { - + this->setCursor(Qt::ArrowCursor); mc->setMouseMode(qmapcontrol::MapControl::Panning); - - + + } - + } /** @@ -366,19 +351,19 @@ void MapWidget::createPathButtonClicked(bool checked) void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordinate) { - + qDebug() << mc->mouseMode(); - + if (QEvent::MouseButtonRelease == event->type() && createPath->isChecked()) { // Create waypoint name QString str; - + str = QString("%1").arg(path->numberOfPoints()); - + // create the WP and set everything in the LineString to display the path Waypoint2DIcon* tempCirclePoint; - + if (mav) { tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle, new QPen(mav->getColor())); @@ -388,19 +373,19 @@ void MapWidget::captureMapClick(const QMouseEvent* event, const QPointF coordina tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle); } mc->layer("Waypoints")->addGeometry(tempCirclePoint); - + qmapcontrol::Point* tempPoint = new qmapcontrol::Point(coordinate.x(), coordinate.y(),str); wps.append(tempPoint); path->addPoint(tempPoint); - + wpIndex.insert(str,tempPoint); - + // Refresh the screen mc->updateRequestNew(); - + // emit signal mouse was clicked emit captureMapCoordinateClick(coordinate); - + } } @@ -409,14 +394,14 @@ void MapWidget::createWaypointGraphAtMap(const QPointF coordinate) if (!wpExists(coordinate)){ // Create waypoint name QString str; - - + + str = QString("%1").arg(path->numberOfPoints()); - + // create the WP and set everything in the LineString to display the path //CirclePoint* tempCirclePoint = new CirclePoint(coordinate.x(), coordinate.y(), 10, str); Waypoint2DIcon* tempCirclePoint; - + if (mav) { tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle, new QPen(mav->getColor())); @@ -425,21 +410,21 @@ void MapWidget::createWaypointGraphAtMap(const QPointF coordinate) { tempCirclePoint = new Waypoint2DIcon(coordinate.x(), coordinate.y(), 20, str, qmapcontrol::Point::Middle); } - - + + mc->layer("Waypoints")->addGeometry(tempCirclePoint); - + Point* tempPoint = new Point(coordinate.x(), coordinate.y(),str); wps.append(tempPoint); path->addPoint(tempPoint); - + wpIndex.insert(str,tempPoint); qDebug()<<"Funcion createWaypointGraphAtMap WP= "< x= "<latitude()<<" y= "<longitude(); - + // Refresh the screen mc->updateRequestNew(); } - + //// // emit signal mouse was clicked // emit captureMapCoordinateClick(coordinate); } @@ -459,40 +444,40 @@ void MapWidget::captureGeometryClick(Geometry* geom, QPoint point) { Q_UNUSED(geom); Q_UNUSED(point); - + mc->setMouseMode(qmapcontrol::MapControl::None); - + } void MapWidget::captureGeometryDrag(Geometry* geom, QPointF coordinate) { - - + + waypointIsDrag = true; - + // Refresh the screen mc->updateRequestNew(); - + int temp = 0; qmapcontrol::Point* point2Find; point2Find = wpIndex[geom->name()]; - + if (point2Find) { point2Find->setCoordinate(coordinate); - + point2Find = dynamic_cast (geom); if (point2Find) { point2Find->setCoordinate(coordinate); - + // qDebug() << geom->name(); temp = geom->get_myIndex(); //qDebug() << temp; emit sendGeometryEndDrag(coordinate,temp); } } - + } void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate) @@ -500,14 +485,14 @@ void MapWidget::captureGeometryEndDrag(Geometry* geom, QPointF coordinate) Q_UNUSED(geom); Q_UNUSED(coordinate); // TODO: Investigate why when creating the waypoint path this slot is being called - + // Only change the mouse mode back to panning when not creating a WP path if (!createPath->isChecked()) { waypointIsDrag = false; mc->setMouseMode(qmapcontrol::MapControl::Panning); } - + } MapWidget::~MapWidget() @@ -520,6 +505,10 @@ MapWidget::~MapWidget() */ void MapWidget::addUAS(UASInterface* uas) { + if(mav != NULL) + { + disconnect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); + } connect(uas, SIGNAL(globalPositionChanged(UASInterface*,double,double,double,quint64)), this, SLOT(updateGlobalPosition(UASInterface*,double,double,double,quint64))); } @@ -555,30 +544,30 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, // A QPen can be used to customize the //pointpen->setWidth(3); //points.append(new CirclePoint(lat, lon, 10, uas->getUASName(), Point::Middle, pointpen)); - + if (!uasIcons.contains(uas->getUASID())) { // Get the UAS color QColor uasColor = uas->getColor(); - + // Icon QPen* pointpen = new QPen(uasColor); qDebug() << uas->getUASName(); MAV2DIcon* p = new MAV2DIcon(lat, lon, 20, uas->getUASName(), qmapcontrol::Point::Middle, pointpen); uasIcons.insert(uas->getUASID(), p); geomLayer->addGeometry(p); - + // Line // A QPen also can use transparency - + QList points; - points.append(new qmapcontrol::Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon))); + points.append(new qmapcontrol::Point(lat, lon, "")); QPen* linepen = new QPen(uasColor.darker()); linepen->setWidth(2); // Add the Points and the QPen to a LineString qmapcontrol::LineString* ls = new qmapcontrol::LineString(points, uas->getUASName(), linepen); uasTrails.insert(uas->getUASID(), ls); - + // Add the LineString to the layer geomLayer->addGeometry(ls); } @@ -591,14 +580,14 @@ void MapWidget::updateGlobalPosition(UASInterface* uas, double lat, double lon, p->setYaw(uas->getYaw()); } // Extend trail - uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(lat, lon, QString("lat: %1 lon: %2").arg(lat, lon))); + uasTrails.value(uas->getUASID())->addPoint(new qmapcontrol::Point(lat, lon, "")); } - - + + // Connect click events of the layer to this object // connect(osmLayer, SIGNAL(geometryClicked(Geometry*, QPoint)), // this, SLOT(geometryClicked(Geometry*, QPoint))); - + // Sets the view to the interesting area updatePosition(0, lat, lon); } @@ -628,10 +617,10 @@ void MapWidget::wheelEvent(QWheelEvent *event) // Detail zoom level is the number of steps zoomed in further // after the bounding has taken effect detailZoom = qAbs(qMin(0, mc->currentZoom()-newZoom)); - + // visual field of camera updateCameraPosition(20*newZoom,0,"no"); - + } void MapWidget::keyPressEvent(QKeyEvent *event) @@ -681,20 +670,20 @@ void MapWidget::changeEvent(QEvent *e) void MapWidget::clearPath() { // Clear the previous WP track - + mc->layer("Waypoints")->clearGeometries(); wps.clear(); path->setPoints(wps); mc->layer("Waypoints")->addGeometry(path); wpIndex.clear(); mc->updateRequestNew(); - - + + if(createPath->isChecked()) { createPath->click(); } - + } void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, float lon) @@ -702,87 +691,88 @@ void MapWidget::changeGlobalWaypointPositionBySpinBox(int index, float lat, floa if(!waypointIsDrag) { qDebug() <<"indice WP= "<setCoordinate(coordinate); - + point2Find = dynamic_cast (mc->layer("Waypoints")->get_Geometry(index)); point2Find->setCoordinate(coordinate); - + // Refresh the screen mc->updateRequestNew(); } - - + + } void MapWidget::updateCameraPosition(double radio, double bearing, QString dir) { + // FIXME Mariano //camPoints.clear(); QPointF currentPos = mc->currentCoordinate(); // QPointF actualPos = getPointxBearing_Range(currentPos.y(),currentPos.x(),bearing,distance); - + // qmapcontrol::Point* tempPoint1 = new qmapcontrol::Point(currentPos.x(), currentPos.y(),"inicial",qmapcontrol::Point::Middle); // qmapcontrol::Point* tempPoint2 = new qmapcontrol::Point(actualPos.x(), actualPos.y(),"final",qmapcontrol::Point::Middle); - + // camPoints.append(tempPoint1); // camPoints.append(tempPoint2); - + // camLine->setPoints(camPoints); - + QPen* camBorderPen = new QPen(QColor(255,0,0)); camBorderPen->setWidth(2); - + //radio = mc->currentZoom() - + if(drawCamBorder) { //clear camera borders mc->layer("Camera")->clearGeometries(); - + //create a camera borders qmapcontrol::CirclePoint* camBorder = new qmapcontrol::CirclePoint(currentPos.x(), currentPos.y(), radio, "camBorder", qmapcontrol::Point::Middle, camBorderPen); - + //camBorder->setCoordinate(currentPos); - + mc->layer("Camera")->addGeometry(camBorder); // mc->layer("Camera")->addGeometry(camLine); mc->updateRequestNew(); - + } else { //clear camera borders mc->layer("Camera")->clearGeometries(); mc->updateRequestNew(); - + } - - + + } void MapWidget::drawBorderCamAtMap(bool status) { drawCamBorder = status; updateCameraPosition(20,0,"no"); - + } QPointF MapWidget::getPointxBearing_Range(double lat1, double lon1, double bearing, double distance) { QPointF temp; - + double rad = M_PI/180; - + bearing = bearing*rad; temp.setX((lon1 + ((distance/60) * (sin(bearing))))); temp.setY((lat1 + ((distance/60) * (cos(bearing))))); - + return temp; } diff --git a/src/ui/RadioCalibration/AirfoilServoCalibrator.cc b/src/ui/RadioCalibration/AirfoilServoCalibrator.cc index 99f134cc8..4d7b587a1 100644 --- a/src/ui/RadioCalibration/AirfoilServoCalibrator.cc +++ b/src/ui/RadioCalibration/AirfoilServoCalibrator.cc @@ -10,7 +10,7 @@ AirfoilServoCalibrator::AirfoilServoCalibrator(AirfoilType type, QWidget *parent /* Add title */ QHBoxLayout *titleLayout = new QHBoxLayout(); - QLabel *title; + QLabel* title; if (type == AILERON) { title = new QLabel(tr("Aileron")); @@ -23,6 +23,10 @@ AirfoilServoCalibrator::AirfoilServoCalibrator(AirfoilType type, QWidget *parent { title = new QLabel(tr("Rudder")); } + else + { + title = new QLabel(tr("Unknown")); + } titleLayout->addWidget(title); grid->addLayout(titleLayout, 0, 0, 1, 3, Qt::AlignHCenter); diff --git a/src/ui/RadioCalibration/RadioCalibrationData.cc b/src/ui/RadioCalibration/RadioCalibrationData.cc index 4d4822ea2..aba6ff1a3 100644 --- a/src/ui/RadioCalibration/RadioCalibrationData.cc +++ b/src/ui/RadioCalibration/RadioCalibrationData.cc @@ -55,6 +55,9 @@ const QVector& RadioCalibrationData::operator ()(int i) const return (*data)[i]; } + // FIXME Bryan + // FIXME James + // This is not good. If it is ever used after being returned it will cause a crash // return QVector(); } diff --git a/src/ui/RadioCalibration/RadioCalibrationWindow.cc b/src/ui/RadioCalibration/RadioCalibrationWindow.cc index 4bc42ada8..4f3c7cf76 100644 --- a/src/ui/RadioCalibration/RadioCalibrationWindow.cc +++ b/src/ui/RadioCalibration/RadioCalibrationWindow.cc @@ -84,6 +84,9 @@ void RadioCalibrationWindow::setChannelRaw(int ch, float raw) void RadioCalibrationWindow::setChannelScaled(int ch, float normalized) { + // FIXME James + // FIXME Bryan + // /** this expects a particular channel to function mapping // \todo allow run-time channel mapping // */ diff --git a/src/ui/SlugsHilSim.cc b/src/ui/SlugsHilSim.cc index 09baad795..a5c584f7c 100644 --- a/src/ui/SlugsHilSim.cc +++ b/src/ui/SlugsHilSim.cc @@ -136,7 +136,9 @@ void SlugsHilSim::activeUasSet(UASInterface* uas){ } -void SlugsHilSim::processHilDatagram(const QByteArray* datagram){ +void SlugsHilSim::processHilDatagram(const QByteArray* datagram) +{ + #ifdef MAVLINK_ENABLED_SLUGS unsigned char i = 0; mavlink_message_t msg; @@ -144,7 +146,6 @@ void SlugsHilSim::processHilDatagram(const QByteArray* datagram){ // GPS mavlink_gps_raw_t tmpGpsRaw; -#ifdef MAVLINK_ENABLED_SLUGS mavlink_gps_date_time_t tmpGpsTime; tmpGpsTime.year = datagram->at(i++); @@ -167,7 +168,6 @@ void SlugsHilSim::processHilDatagram(const QByteArray* datagram){ mavlink_msg_gps_date_time_encode(MG::SYSTEM::ID,MG::SYSTEM::COMPID, &msg, &tmpGpsTime); activeUas->sendMessage(hilLink, msg); -#endif memset(&msg, 0, sizeof(mavlink_message_t)); @@ -180,6 +180,9 @@ void SlugsHilSim::processHilDatagram(const QByteArray* datagram){ ui->ed_1->setText(QString::number(tmpGpsRaw.hdg)); ui->ed_2->setText(QString::number(tmpGpsRaw.v)); ui->ed_3->setText(QString::number(tmpGpsRaw.eph)); +#else + Q_UNUSED(datagram); +#endif } float SlugsHilSim::getFloatFromDatagram (const QByteArray* datagram, unsigned char * i){ @@ -205,4 +208,5 @@ uint16_t SlugsHilSim::getUint16FromDatagram (const QByteArray* datagram, unsigne void SlugsHilSim::linkSelected(int cbIndex){ //hilLink = linksAvailable + // FIXME Mariano } diff --git a/src/ui/WaypointList.cc b/src/ui/WaypointList.cc index d2d4aaeb2..2632a1b71 100644 --- a/src/ui/WaypointList.cc +++ b/src/ui/WaypointList.cc @@ -570,5 +570,7 @@ void WaypointList::setIsLoadFileWP() void WaypointList::setIsReadGlobalWP(bool value) { - // readGlobalWP = value; + // FIXME James Check this + Q_UNUSED(value); + // readGlobalWP = value; } diff --git a/src/ui/map3D/QGCGoogleEarthView.cc b/src/ui/map3D/QGCGoogleEarthView.cc index aab70853b..63eb87c48 100644 --- a/src/ui/map3D/QGCGoogleEarthView.cc +++ b/src/ui/map3D/QGCGoogleEarthView.cc @@ -178,7 +178,7 @@ void QGCGoogleEarthView::showTrail(bool state) void QGCGoogleEarthView::showWaypoints(bool state) { - + waypointsEnabled = state; } void QGCGoogleEarthView::follow(bool follow) @@ -232,7 +232,7 @@ void QGCGoogleEarthView::showEvent(QShowEvent* event) // Reloading the webpage, this resets Google Earth gEarthInitialized = false; - QTimer::singleShot(2000, this, SLOT(initializeGoogleEarth())); + QTimer::singleShot(3000, this, SLOT(initializeGoogleEarth())); updateTimer->start(refreshRateMs); } } @@ -299,7 +299,7 @@ void QGCGoogleEarthView::initializeGoogleEarth() qDebug() << "COULD NOT GET DOCUMENT OBJECT! Aborting"; } #endif - QTimer::singleShot(2500, this, SLOT(initializeGoogleEarth())); + QTimer::singleShot(3500, this, SLOT(initializeGoogleEarth())); return; } diff --git a/src/ui/map3D/QOSGWidget.cc b/src/ui/map3D/QOSGWidget.cc index 12029e208..c97eab99d 100644 --- a/src/ui/map3D/QOSGWidget.cc +++ b/src/ui/map3D/QOSGWidget.cc @@ -26,7 +26,7 @@ QOSGWidget::QOSGWidget( QWidget * parent, const char * name, WindowFlags f, bool QWidget(parent, f), _overrideTraits (overrideTraits) { createContext(); - + Q_UNUSED(name); setAttribute(Qt::WA_PaintOnScreen); setAttribute(Qt::WA_NoSystemBackground); setFocusPolicy(Qt::ClickFocus); @@ -95,6 +95,8 @@ void QOSGWidget::createContext() #ifndef WIN32 void QOSGWidget::destroyEvent(bool destroyWindow, bool destroySubWindows) { + Q_UNUSED(destroyWindow); + Q_UNUSED(destroySubWindows); _gw->getEventQueue()->closeWindow(); } @@ -236,7 +238,7 @@ class QViewerTimer : public QWidget _timer.stop (); } - virtual void paintEvent (QPaintEvent * event) { _viewer->frame(); } + virtual void paintEvent (QPaintEvent * event) { Q_UNUSED(event); _viewer->frame(); } osg::ref_ptr _viewer; QTimer _timer; -- 2.22.0